Skip to content

Commit 3deb91a

Browse files
paudrowjacobperron
andauthored
Revert 657 audrow/add qos overrides (#670)
* Remove try-catch blocks around declare_parameter (#663) Try-catches were added in #631 due to a new rclcpp feature enforcing static parameter. The behavior was later patched for this particular use-case in ros2/rclcpp#1673, so now we can avoid having to try-catch. Signed-off-by: Jacob Perron <jacob@openrobotics.org> * Add missing message_filters dependency (#666) Headers from message_filters are included here: https://github.com/cra-ros-pkg/robot_localization/blob/67098c2341b5d1ccbcceb8eede60e79db74814a6/include/robot_localization/ros_robot_localization_listener.h\#L41-L42 Signed-off-by: Jacob Perron <jacob@openrobotics.org> * Revert "Enable QoS overrides (#657)" This reverts commit 2816e92. Co-authored-by: Jacob Perron <jacob@openrobotics.org>
1 parent 04cf96f commit 3deb91a

File tree

4 files changed

+11
-39
lines changed

4 files changed

+11
-39
lines changed

include/robot_localization/ros_robot_localization_listener.hpp

Lines changed: 1 addition & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -49,18 +49,6 @@
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-
6452
//! @brief RosRobotLocalizationListener class
6553
//!
6654
//! This class wraps the RobotLocalizationEstimator. It listens to topics over
@@ -82,10 +70,7 @@ class RosRobotLocalizationListener
8270
//!
8371
//! @param[in] node - rclcpp node shared pointer
8472
//!
85-
explicit RosRobotLocalizationListener(
86-
rclcpp::Node::SharedPtr node,
87-
rclcpp::SubscriptionOptions options =
88-
detail::get_subscription_options_with_default_qos_override_policies());
73+
explicit RosRobotLocalizationListener(rclcpp::Node::SharedPtr node);
8974

9075
//! @brief Destructor
9176
//!

src/navsat_transform.cpp

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

171171
auto custom_qos = rclcpp::SensorDataQoS(rclcpp::KeepLast(1));
172172

173-
auto subscriber_options = rclcpp::SubscriptionOptions();
174-
subscriber_options.qos_overriding_options =
175-
rclcpp::QosOverridingOptions::with_default_policies();
176173
odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>(
177-
"odometry/filtered", custom_qos, std::bind(
178-
&NavSatTransform::odomCallback, this, _1), subscriber_options);
174+
"odometry/filtered", custom_qos, std::bind(&NavSatTransform::odomCallback, this, _1));
179175

180176
gps_sub_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
181-
"gps/fix", custom_qos, std::bind(&NavSatTransform::gpsFixCallback, this, _1),
182-
subscriber_options);
177+
"gps/fix", custom_qos, std::bind(&NavSatTransform::gpsFixCallback, this, _1));
183178

184179
if (!use_odometry_yaw_ && !use_manual_datum_) {
185180
imu_sub_ = this->create_subscription<sensor_msgs::msg::Imu>(
186-
"imu", custom_qos, std::bind(&NavSatTransform::imuCallback, this, _1), subscriber_options);
181+
"imu", custom_qos, std::bind(&NavSatTransform::imuCallback, this, _1));
187182
}
188183

189-
rclcpp::PublisherOptions publisher_options;
190-
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
191184
gps_odom_pub_ =
192-
this->create_publisher<nav_msgs::msg::Odometry>(
193-
"odometry/gps", rclcpp::QoS(10), publisher_options);
185+
this->create_publisher<nav_msgs::msg::Odometry>("odometry/gps", rclcpp::QoS(10));
194186

195187
if (publish_gps_) {
196188
filtered_gps_pub_ =
197-
this->create_publisher<sensor_msgs::msg::NavSatFix>(
198-
"gps/filtered", rclcpp::QoS(10), publisher_options);
189+
this->create_publisher<sensor_msgs::msg::NavSatFix>("gps/filtered", rclcpp::QoS(10));
199190
}
200191

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

src/ros_filter.cpp

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

19721972
// Position publisher
1973-
rclcpp::PublisherOptions publisher_options;
1974-
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
19751973
position_pub_ =
1976-
this->create_publisher<nav_msgs::msg::Odometry>(
1977-
"odometry/filtered", rclcpp::QoS(10), publisher_options);
1974+
this->create_publisher<nav_msgs::msg::Odometry>("odometry/filtered", rclcpp::QoS(10));
19781975

19791976
// Optional acceleration publisher
19801977
if (publish_acceleration_) {
19811978
accel_pub_ =
19821979
this->create_publisher<geometry_msgs::msg::AccelWithCovarianceStamped>(
1983-
"accel/filtered", rclcpp::QoS(10), publisher_options);
1980+
"accel/filtered", rclcpp::QoS(10));
19841981
}
19851982

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

src/ros_robot_localization_listener.cpp

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

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

0 commit comments

Comments
 (0)