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

Use latched QoS for Extrinsic topic when intra-process is used #2619

Merged
merged 2 commits into from
Feb 9, 2023
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
1 change: 0 additions & 1 deletion realsense2_camera/include/base_realsense_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -275,7 +275,6 @@ namespace realsense2_camera
std::map<stream_index_pair, rclcpp::Publisher<realsense2_camera_msgs::msg::Metadata>::SharedPtr> _metadata_publishers;
std::map<stream_index_pair, rclcpp::Publisher<IMUInfo>::SharedPtr> _imu_info_publisher;
std::map<stream_index_pair, rclcpp::Publisher<Extrinsics>::SharedPtr> _extrinsics_publishers;
std::map<stream_index_pair, Extrinsics> _extrinsics_msgs;
std::map<stream_index_pair, cv::Mat> _image;
std::map<unsigned int, std::string> _encoding;

Expand Down
19 changes: 1 addition & 18 deletions realsense2_camera/src/base_realsense_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,7 @@ BaseRealSenseNode::BaseRealSenseNode(rclcpp::Node& node,
ROS_INFO("Intra-Process communication enabled");
}

// intra-process do not support latched QoS, so we need to disable intra-process for this topic
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
#ifndef DASHING
Expand Down Expand Up @@ -864,7 +865,6 @@ void BaseRealSenseNode::publishExtrinsicsTopic(const stream_index_pair& sip, con
Extrinsics msg = rsExtrinsicsToMsg(ex);
if (_extrinsics_publishers.find(sip) != _extrinsics_publishers.end())
{
_extrinsics_msgs[sip] = msg; // We keep the message for periodically publish later if needed
_extrinsics_publishers[sip]->publish(msg);
}
}
Expand Down Expand Up @@ -1012,23 +1012,6 @@ void BaseRealSenseNode::publishDynamicTransforms()
{
ROS_ERROR_STREAM("Error publishing dynamic transforms: " << e.what());
}

// If static_tf was not created we need to publish the extrinsics periodically since it is not publishes as a latched topic.
if ( !_static_tf_broadcaster )
{
try
{
for (const auto &extrinsics_publisher : _extrinsics_publishers)
{
const auto &ext_msg = _extrinsics_msgs[extrinsics_publisher.first];
extrinsics_publisher.second->publish( ext_msg );
}
}
catch (const std::exception &e)
{
ROS_ERROR_STREAM("Error publishing extrinsics : " << e.what());
}
}
}
}
}
Expand Down
10 changes: 6 additions & 4 deletions realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,6 @@ void BaseRealSenseNode::stopPublishers(const std::vector<stream_profile>& profil
}
_metadata_publishers.erase(sip);
_extrinsics_publishers.erase(sip);
_extrinsics_msgs.erase(sip);
}
}

Expand Down Expand Up @@ -286,12 +285,15 @@ void BaseRealSenseNode::startPublishers(const std::vector<stream_profile>& profi

if (!((rs2::stream_profile)profile==(rs2::stream_profile)_base_profile))
{
// When intra process is on we cannot use latched qos, we will need to send this message periodically with volatile durability
rmw_qos_profile_t extrinsics_qos = _use_intra_process ? rmw_qos_profile_default : rmw_qos_profile_latched;

// intra-process do not support latched QoS, so we need to disable intra-process for this topic
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
rmw_qos_profile_t extrinsics_qos = rmw_qos_profile_latched;

std::string topic_extrinsics("extrinsics/" + create_graph_resource_name(ros_stream_to_string(_base_profile.stream_type()) + "_to_" + stream_name));
_extrinsics_publishers[sip] = _node.create_publisher<realsense2_camera_msgs::msg::Extrinsics>(topic_extrinsics,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(extrinsics_qos), extrinsics_qos));
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(extrinsics_qos), extrinsics_qos), std::move(options));
}
}
}
Expand Down