diff --git a/README.md b/README.md index aacd361d24..380dc9a5a7 100644 --- a/README.md +++ b/README.md @@ -83,7 +83,7 @@ If using D435 or D415, the gyro and accel topics wont be available. Likewise, ot ### Launch parameters The following parameters are available by the wrapper: - **serial_no**: will attach to the device with the given serial number (*serial_no*) number. Default, attach to available RealSense device in random. -- **port_no**: will attach to the device with the given USB port (*port_no*). i.e 4-1, 4-2 etc. Default, ignore USB port when choosing a device. +- **usb_port_id**: will attach to the device with the given USB port (*usb_port_id*). i.e 4-1, 4-2 etc. Default, ignore USB port when choosing a device. - **device_type**: will attach to a device whose name includes the given *device_type* regular expression pattern. Default, ignore device type. For example, device_type:=d435 will match d435 and d435i. device_type=d435(?!i) will match d435 but not d435i. - **rosbag_filename**: Will publish topics from rosbag file. diff --git a/realsense2_camera/include/realsense_node_factory.h b/realsense2_camera/include/realsense_node_factory.h index 423e02b535..0a345c52a4 100644 --- a/realsense2_camera/include/realsense_node_factory.h +++ b/realsense2_camera/include/realsense_node_factory.h @@ -68,7 +68,7 @@ namespace realsense2_camera std::unique_ptr _realSenseNode; rs2::context _ctx; std::string _serial_no; - std::string _port_no; + std::string _usb_port_id; std::string _device_type; bool _initial_reset; std::thread _query_thread; diff --git a/realsense2_camera/launch/includes/nodelet.launch.xml b/realsense2_camera/launch/includes/nodelet.launch.xml index f8f3a16be3..d780c1ee23 100644 --- a/realsense2_camera/launch/includes/nodelet.launch.xml +++ b/realsense2_camera/launch/includes/nodelet.launch.xml @@ -2,7 +2,7 @@ - + @@ -93,7 +93,7 @@ - + diff --git a/realsense2_camera/launch/rs_camera.launch b/realsense2_camera/launch/rs_camera.launch index e02cbfbaf6..3039390dff 100644 --- a/realsense2_camera/launch/rs_camera.launch +++ b/realsense2_camera/launch/rs_camera.launch @@ -1,6 +1,6 @@ - + @@ -60,7 +60,7 @@ - + diff --git a/realsense2_camera/launch/rs_rgbd.launch b/realsense2_camera/launch/rs_rgbd.launch index 6e633beaec..cdd74ad62f 100644 --- a/realsense2_camera/launch/rs_rgbd.launch +++ b/realsense2_camera/launch/rs_rgbd.launch @@ -48,7 +48,7 @@ Processing enabled by this node: - + @@ -119,7 +119,7 @@ Processing enabled by this node: - + diff --git a/realsense2_camera/launch/rs_t265.launch b/realsense2_camera/launch/rs_t265.launch index 9d7ce67074..fc687a49b2 100644 --- a/realsense2_camera/launch/rs_t265.launch +++ b/realsense2_camera/launch/rs_t265.launch @@ -6,7 +6,7 @@ https://github.com/IntelRealSense/librealsense/blob/master/third-party/libtm/lib --> - + @@ -35,7 +35,7 @@ https://github.com/IntelRealSense/librealsense/blob/master/third-party/libtm/lib - + diff --git a/realsense2_camera/src/realsense_node_factory.cpp b/realsense2_camera/src/realsense_node_factory.cpp index 529479e2d2..82e56427e7 100644 --- a/realsense2_camera/src/realsense_node_factory.cpp +++ b/realsense2_camera/src/realsense_node_factory.cpp @@ -95,7 +95,7 @@ void RealSenseNodeFactory::getDevice(rs2::device_list list) { std::stringstream msg; msg << "Error extracting usb port from device with physical ID: " << pn << std::endl << "Please report on github issue at https://github.com/IntelRealSense/realsense-ros"; - if (_port_no.empty()) + if (_usb_port_id.empty()) { ROS_WARN_STREAM(msg.str()); } @@ -112,7 +112,7 @@ void RealSenseNodeFactory::getDevice(rs2::device_list list) found_device_type = std::regex_search(name, base_match, device_type_regex); } - if ((_serial_no.empty() || sn == _serial_no) && (_port_no.empty() || port_id == _port_no) && found_device_type) + if ((_serial_no.empty() || sn == _serial_no) && (_usb_port_id.empty() || port_id == _usb_port_id) && found_device_type) { _device = dev; _serial_no = sn; @@ -130,13 +130,13 @@ void RealSenseNodeFactory::getDevice(rs2::device_list list) msg += "serial number " + _serial_no; add_and = true; } - if (!_port_no.empty()) + if (!_usb_port_id.empty()) { if (add_and) { msg += " and "; } - msg += "port number " + _port_no; + msg += "usb port id " + _usb_port_id; add_and = true; } if (!_device_type.empty()) @@ -211,7 +211,7 @@ void RealSenseNodeFactory::onInit() ros::NodeHandle nh = getNodeHandle(); auto privateNh = getPrivateNodeHandle(); privateNh.param("serial_no", _serial_no, std::string("")); - privateNh.param("port_no", _port_no, std::string("")); + privateNh.param("usb_port_id", _usb_port_id, std::string("")); privateNh.param("device_type", _device_type, std::string("")); std::string rosbag_filename("");