Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

stereo_image_proc: disparity_node: Add parameter to control camera_info #1051

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions stereo_image_proc/doc/components.rst
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,9 @@ Parameters
over the network than camera info and/or the delay from disparity processing
is too long.

*Common*
* **use_image_transport_camera_info** (bool, default: true): To control whether DisparityNode uses image_transport::getCameraInfoTopic for deriving camera_info topics. To set false, the node directly uses the camera_info topics specified via remapping (e.g., left/camera_info and right/camera_info), bypassing image_transport's derivation logic.

stereo_image_proc::PointCloudNode
---------------------------------
Combines a rectified color image and disparity image to produce a
Expand Down
23 changes: 17 additions & 6 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ class DisparityNode : public rclcpp::Node
SEMI_GLOBAL_BLOCK_MATCHING
};

bool use_image_transport_camera_info;
// Subscriptions
image_transport::SubscriberFilter sub_l_image_, sub_r_image_;
message_filters::Subscriber<sensor_msgs::msg::CameraInfo> sub_l_info_, sub_r_info_;
Expand Down Expand Up @@ -170,6 +171,8 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
bool approx = this->declare_parameter("approximate_sync", false);
double approx_sync_epsilon = this->declare_parameter("approximate_sync_tolerance_seconds", 0.0);
this->declare_parameter("use_system_default_qos", false);
use_image_transport_camera_info = this->declare_parameter("use_image_transport_camera_info",
true);

// Synchronize callbacks
if (approx) {
Expand Down Expand Up @@ -307,12 +310,20 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
std::string right_topic =
node_base->resolve_topic_or_service_name("right/image_rect", false);
// Allow also remapping camera_info to something different than default
std::string left_info_topic =
node_base->resolve_topic_or_service_name(
image_transport::getCameraInfoTopic(left_topic), false);
std::string right_info_topic =
node_base->resolve_topic_or_service_name(
image_transport::getCameraInfoTopic(right_topic), false);
std::string left_info_topic;
std::string right_info_topic;

if (use_image_transport_camera_info) {
// Use image_transport to derive camera_info topics
left_info_topic = node_base->resolve_topic_or_service_name(
image_transport::getCameraInfoTopic(left_topic), false);
right_info_topic = node_base->resolve_topic_or_service_name(
image_transport::getCameraInfoTopic(right_topic), false);
} else {
// Use default camera_info topics
left_info_topic = node_base->resolve_topic_or_service_name("left/camera_info", false);
right_info_topic = node_base->resolve_topic_or_service_name("right/camera_info", false);
}

// REP-2003 specifies that subscriber should be SensorDataQoS
const auto sensor_data_qos = rclcpp::SensorDataQoS();
Expand Down