Skip to content

Commit

Permalink
updated QoS of IMU topic
Browse files Browse the repository at this point in the history
  • Loading branch information
Arun-Prasad-V committed Sep 7, 2023
1 parent 6fdfaa0 commit 41ae997
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion realsense2_camera/src/rs_node_setup.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,7 +311,10 @@ void BaseRealSenseNode::startPublishers(const std::vector<stream_profile>& profi
}
if (_is_accel_enabled && _is_gyro_enabled && (_imu_sync_method > imu_sync_method::NONE))
{
_synced_imu_publisher = std::make_shared<SyncedImuPublisher>(_node.create_publisher<sensor_msgs::msg::Imu>("~/imu", 5));
rmw_qos_profile_t qos = _use_intra_process ? qos_string_to_qos(DEFAULT_QOS) : qos_string_to_qos(HID_QOS);

_synced_imu_publisher = std::make_shared<SyncedImuPublisher>(_node.create_publisher<sensor_msgs::msg::Imu>("~/imu",
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos)));
}

}
Expand Down

0 comments on commit 41ae997

Please sign in to comment.