Skip to content

Commit 2816e92

Browse files
authored
Enable QoS overrides (#657)
* Enable QoS overrides Signed-off-by: Audrow Nash <[email protected]> * Use SubscriptionOptions Signed-off-by: Audrow Nash <[email protected]> * Use with_default_policies Signed-off-by: Audrow Nash <[email protected]> * Use with_default_policies in ros_filter Signed-off-by: Audrow Nash <[email protected]> * Improve formatting Signed-off-by: Audrow Nash <[email protected]>
1 parent d27e8cb commit 2816e92

File tree

4 files changed

+39
-11
lines changed

4 files changed

+39
-11
lines changed

include/robot_localization/ros_robot_localization_listener.hpp

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,18 @@
4949
namespace robot_localization
5050
{
5151

52+
namespace detail
53+
{
54+
rclcpp::SubscriptionOptions
55+
get_subscription_options_with_default_qos_override_policies()
56+
{
57+
auto subscription_options = rclcpp::SubscriptionOptions();
58+
subscription_options.qos_overriding_options =
59+
rclcpp::QosOverridingOptions::with_default_policies();
60+
return subscription_options;
61+
}
62+
} // namespace detail
63+
5264
//! @brief RosRobotLocalizationListener class
5365
//!
5466
//! This class wraps the RobotLocalizationEstimator. It listens to topics over
@@ -70,7 +82,10 @@ class RosRobotLocalizationListener
7082
//!
7183
//! @param[in] node - rclcpp node shared pointer
7284
//!
73-
explicit RosRobotLocalizationListener(rclcpp::Node::SharedPtr node);
85+
explicit RosRobotLocalizationListener(
86+
rclcpp::Node::SharedPtr node,
87+
rclcpp::SubscriptionOptions options =
88+
detail::get_subscription_options_with_default_qos_override_policies());
7489

7590
//! @brief Destructor
7691
//!

src/navsat_transform.cpp

Lines changed: 14 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -141,23 +141,32 @@ NavSatTransform::NavSatTransform(const rclcpp::NodeOptions & options)
141141

142142
auto custom_qos = rclcpp::SensorDataQoS(rclcpp::KeepLast(1));
143143

144+
auto subscriber_options = rclcpp::SubscriptionOptions();
145+
subscriber_options.qos_overriding_options =
146+
rclcpp::QosOverridingOptions::with_default_policies();
144147
odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>(
145-
"odometry/filtered", custom_qos, std::bind(&NavSatTransform::odomCallback, this, _1));
148+
"odometry/filtered", custom_qos, std::bind(
149+
&NavSatTransform::odomCallback, this, _1), subscriber_options);
146150

147151
gps_sub_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
148-
"gps/fix", custom_qos, std::bind(&NavSatTransform::gpsFixCallback, this, _1));
152+
"gps/fix", custom_qos, std::bind(&NavSatTransform::gpsFixCallback, this, _1),
153+
subscriber_options);
149154

150155
if (!use_odometry_yaw_ && !use_manual_datum_) {
151156
imu_sub_ = this->create_subscription<sensor_msgs::msg::Imu>(
152-
"imu", custom_qos, std::bind(&NavSatTransform::imuCallback, this, _1));
157+
"imu", custom_qos, std::bind(&NavSatTransform::imuCallback, this, _1), subscriber_options);
153158
}
154159

160+
rclcpp::PublisherOptions publisher_options;
161+
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
155162
gps_odom_pub_ =
156-
this->create_publisher<nav_msgs::msg::Odometry>("odometry/gps", rclcpp::QoS(10));
163+
this->create_publisher<nav_msgs::msg::Odometry>(
164+
"odometry/gps", rclcpp::QoS(10), publisher_options);
157165

158166
if (publish_gps_) {
159167
filtered_gps_pub_ =
160-
this->create_publisher<sensor_msgs::msg::NavSatFix>("gps/filtered", rclcpp::QoS(10));
168+
this->create_publisher<sensor_msgs::msg::NavSatFix>(
169+
"gps/filtered", rclcpp::QoS(10), publisher_options);
161170
}
162171

163172
// Sleep for the parameterized amount of time, to give

src/ros_filter.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2002,14 +2002,17 @@ void RosFilter<T>::initialize()
20022002
tf2::toMsg(tf2::Transform::getIdentity());
20032003

20042004
// Position publisher
2005+
rclcpp::PublisherOptions publisher_options;
2006+
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
20052007
position_pub_ =
2006-
this->create_publisher<nav_msgs::msg::Odometry>("odometry/filtered", rclcpp::QoS(10));
2008+
this->create_publisher<nav_msgs::msg::Odometry>(
2009+
"odometry/filtered", rclcpp::QoS(10), publisher_options);
20072010

20082011
// Optional acceleration publisher
20092012
if (publish_acceleration_) {
20102013
accel_pub_ =
20112014
this->create_publisher<geometry_msgs::msg::AccelWithCovarianceStamped>(
2012-
"accel/filtered", rclcpp::QoS(10));
2015+
"accel/filtered", rclcpp::QoS(10), publisher_options);
20132016
}
20142017

20152018
const std::chrono::duration<double> timespan{1.0 / frequency_};

src/ros_robot_localization_listener.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -75,11 +75,12 @@ FilterTypes::FilterType filterTypeFromString(
7575
}
7676

7777
RosRobotLocalizationListener::RosRobotLocalizationListener(
78-
rclcpp::Node::SharedPtr node)
78+
rclcpp::Node::SharedPtr node,
79+
rclcpp::SubscriptionOptions options)
7980
: qos1_(1),
8081
qos10_(10),
81-
odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile()),
82-
accel_sub_(node, "acceleration/filtered", qos1_.get_rmw_qos_profile()),
82+
odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile(), options),
83+
accel_sub_(node, "acceleration/filtered", qos1_.get_rmw_qos_profile(), options),
8384
sync_(odom_sub_, accel_sub_, 10u),
8485
node_clock_(node->get_node_clock_interface()->get_clock()),
8586
node_logger_(node->get_node_logging_interface()),

0 commit comments

Comments
 (0)