Skip to content

Commit

Permalink
support latched QoS for imu_info
Browse files Browse the repository at this point in the history
  • Loading branch information
SamerKhshiboun committed Oct 8, 2024
1 parent f57a617 commit 9f37e29
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,13 +296,13 @@ void BaseRealSenseNode::startPublishers(const std::vector<stream_profile>& profi
// Publish Intrinsics:
info_topic_name << "~/" << stream_name << "/imu_info";

// QoS settings for Latching-like behavior for the imu_info topic
// History: KeepLast(1) - Retains only the last message
// Durability: Transient Local - Ensures that late subscribers get the last message that was published
// Reliability: Ensures reliable delivery of messages
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable();
_imu_info_publishers[sip] = _node.create_publisher<IMUInfo>(info_topic_name.str(), qos);

// IMU Info will have latched QoS, and it will publish its data only once during the ROS Node lifetime.
// 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;
_imu_info_publishers[sip] = _node.create_publisher<IMUInfo>(info_topic_name.str(),
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_latched), rmw_qos_profile_latched),
std::move(options));
IMUInfo info_msg = getImuInfo(profile);
_imu_info_publishers[sip]->publish(info_msg);
}
Expand Down

0 comments on commit 9f37e29

Please sign in to comment.