Skip to content

Commit 4704100

Browse files
committed
Update README.MD
1 parent 65ee492 commit 4704100

File tree

3 files changed

+45
-20
lines changed

3 files changed

+45
-20
lines changed

README.MD

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -237,7 +237,7 @@ For optimal performance, we strongly recommend updating to the latest firmware v
237237
| Gemini 336 | 1.2.20 | gemini_330_series.launch.py |
238238
| Gemini 336L | 1.2.20 | gemini_330_series.launch.py |
239239
| Gemini 335Le | 1.5.31 | gemini_330_series.launch.py |
240-
| Gemini 435Le | / | gemini_330_series.launch.py |
240+
| Gemini 435Le | 1.2.04 | gemini435_le.launch.py |
241241
| Femto Bolt | 1.1.2 | femto_bolt.launch.py |
242242
| Femto Mega | 1.3.0 | femto_mega.launch.py |
243243
| Astra 2 | 2.8.20 | astra2.launch.py |
@@ -438,12 +438,18 @@ When using Femto Mega, Gemini 335Le and Gemini 435Le, you can use the network to
438438
ros2 launch orbbec_camera femto_mega.launch.py enumerate_net_device:=true
439439
```
440440

441-
**Gemini 335Le & Gemini 435Le:**
441+
**Gemini 335Le:**
442442

443443
```bash
444444
ros2 launch orbbec_camera gemini_330_series.launch.py enumerate_net_device:=true
445445
```
446446

447+
**Gemini 435Le:**
448+
449+
```bash
450+
ros2 launch orbbec_camera gemini435_le.launch.py enumerate_net_device:=true
451+
```
452+
447453
For more information about network device enumeration.Reference:[Network device documentation](./orbbec_camera/examples/net_camera/)
448454

449455
### GMSL device enumeration

orbbec_camera/examples/net_camera/README.MD

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
> This section describes how to use Net camera in OrbbecSDK_ROS2.Currently, only Femto_Mega, Gemini 335Le and Gemini 435Le devices are supported, and other Net devices will be supported in the near future.
44
5-
## Femto Mega
5+
## Femto Mega & Gemini 435Le
66

77
### Parameter Introduction
88

@@ -16,6 +16,8 @@ If you do not want to automatically enumerate network devices,you can set `enume
1616

1717
### Single Net camera
1818

19+
> If you need to run Gemini 435Le, you only need to replace [femto_mega.launch.py ](../../launch/femto_mega.launch.py)in the run command with [gemini435_le.launch.py](../../launch/gemini435_le.launch.py)
20+
1921
For [femto_mega.launch.py](../../launch/femto_mega.launch.py) as an example:
2022

2123
#### automatically enumerate network devices:
@@ -32,7 +34,7 @@ Note: `net_device_ip` needs to be changed to the IP address of the device, here
3234
ros2 launch orbbec_camera femto_mega.launch.py enumerate_net_device:=false net_device_ip:=192.168.1.10 net_device_port:=8090
3335
```
3436

35-
## Gemini 335Le & Gemini 435Le
37+
## Gemini 335Le
3638

3739
Network device settings: `enumerate_net_device` must be set to true, set `net_device_ip` to the IP address of the device, and set `net_device_port` to the default value of 8090.
3840

orbbec_camera/tools/list_devices_node.cpp

Lines changed: 33 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -20,25 +20,42 @@
2020

2121
int main() {
2222
try {
23+
ob::Context::setLoggerSeverity(OBLogSeverity::OB_LOG_SEVERITY_OFF);
2324
auto context = std::make_unique<ob::Context>();
24-
context->setLoggerSeverity(OBLogSeverity::OB_LOG_SEVERITY_OFF);
2525
auto list = context->queryDeviceList();
2626
for (size_t i = 0; i < list->deviceCount(); i++) {
27-
auto device = list->getDevice(i);
28-
auto device_info = device->getDeviceInfo();
29-
std::string serial = device_info->serialNumber();
30-
std::string uid = device_info->uid();
31-
auto usb_port = orbbec_camera::parseUsbPort(uid);
32-
std::stringstream pid_hex;
33-
pid_hex<< std::hex << std::setw(4) << std::setfill('0') << device_info->getPid();
34-
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
35-
"- Name: " << device_info->getName() << ", PID: 0x"
36-
<< pid_hex.str() << ", SN/ID: " << serial
37-
<< ", Connection: " << device_info->getConnectionType());
38-
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "serial: " << serial);
39-
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "usb port: " << usb_port);
40-
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
41-
"usb connect type: " << device_info->getConnectionType());
27+
if (std::string(list->getConnectionType(i)) != "Ethernet") {
28+
std::string serial = list->serialNumber(i);
29+
std::string uid = list->uid(i);
30+
auto usb_port = orbbec_camera::parseUsbPort(uid);
31+
auto connection_type = list->getConnectionType(i);
32+
std::stringstream pid_hex;
33+
pid_hex << std::hex << std::setw(4) << std::setfill('0') << list->getPid(i);
34+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
35+
"- Name: " << list->getName(i) << ", PID: 0x" << pid_hex.str()
36+
<< ", SN/ID: " << serial
37+
<< ", Connection: " << connection_type);
38+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "serial: " << serial);
39+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "usb port: " << usb_port);
40+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
41+
"usb connect type: " << connection_type);
42+
std::cout << std::endl;
43+
} else {
44+
std::string serial = list->serialNumber(i);
45+
auto connection_type = list->getConnectionType(i);
46+
auto ip_address = list->getIpAddress(i);
47+
std::stringstream pid_hex;
48+
pid_hex << std::hex << std::setw(4) << std::setfill('0') << list->getPid(i);
49+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
50+
"- Name: " << list->getName(i) << ", PID: 0x" << pid_hex.str()
51+
<< ", SN/ID: " << serial
52+
<< ", Connection: " << connection_type);
53+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "serial: " << serial);
54+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"), "ip address: " << ip_address);
55+
RCLCPP_INFO_STREAM(rclcpp::get_logger("list_device_node"),
56+
"usb connect type: " << connection_type);
57+
std::cout << std::endl;
58+
}
4259
}
4360
} catch (ob::Error &e) {
4461
RCLCPP_ERROR_STREAM(rclcpp::get_logger("list_device_node"), e.getMessage());

0 commit comments

Comments
 (0)