Skip to content

Commit

Permalink
Revert 657 audrow/add qos overrides (#670)
Browse files Browse the repository at this point in the history
* 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 <[email protected]>

* 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 <[email protected]>

* Revert "Enable QoS overrides (#657)"

This reverts commit 2816e92.

Co-authored-by: Jacob Perron <[email protected]>
  • Loading branch information
paudrow and jacobperron authored May 25, 2021
1 parent 04cf96f commit 3deb91a
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 39 deletions.
17 changes: 1 addition & 16 deletions include/robot_localization/ros_robot_localization_listener.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,18 +49,6 @@
namespace robot_localization
{

namespace detail
{
rclcpp::SubscriptionOptions
get_subscription_options_with_default_qos_override_policies()
{
auto subscription_options = rclcpp::SubscriptionOptions();
subscription_options.qos_overriding_options =
rclcpp::QosOverridingOptions::with_default_policies();
return subscription_options;
}
} // namespace detail

//! @brief RosRobotLocalizationListener class
//!
//! This class wraps the RobotLocalizationEstimator. It listens to topics over
Expand All @@ -82,10 +70,7 @@ class RosRobotLocalizationListener
//!
//! @param[in] node - rclcpp node shared pointer
//!
explicit RosRobotLocalizationListener(
rclcpp::Node::SharedPtr node,
rclcpp::SubscriptionOptions options =
detail::get_subscription_options_with_default_qos_override_policies());
explicit RosRobotLocalizationListener(rclcpp::Node::SharedPtr node);

//! @brief Destructor
//!
Expand Down
19 changes: 5 additions & 14 deletions src/navsat_transform.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,32 +170,23 @@ NavSatTransform::NavSatTransform(const rclcpp::NodeOptions & options)

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

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

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

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

rclcpp::PublisherOptions publisher_options;
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
gps_odom_pub_ =
this->create_publisher<nav_msgs::msg::Odometry>(
"odometry/gps", rclcpp::QoS(10), publisher_options);
this->create_publisher<nav_msgs::msg::Odometry>("odometry/gps", rclcpp::QoS(10));

if (publish_gps_) {
filtered_gps_pub_ =
this->create_publisher<sensor_msgs::msg::NavSatFix>(
"gps/filtered", rclcpp::QoS(10), publisher_options);
this->create_publisher<sensor_msgs::msg::NavSatFix>("gps/filtered", rclcpp::QoS(10));
}

// Sleep for the parameterized amount of time, to give
Expand Down
7 changes: 2 additions & 5 deletions src/ros_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1970,17 +1970,14 @@ void RosFilter<T>::initialize()
tf2::toMsg(tf2::Transform::getIdentity());

// Position publisher
rclcpp::PublisherOptions publisher_options;
publisher_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
position_pub_ =
this->create_publisher<nav_msgs::msg::Odometry>(
"odometry/filtered", rclcpp::QoS(10), publisher_options);
this->create_publisher<nav_msgs::msg::Odometry>("odometry/filtered", rclcpp::QoS(10));

// Optional acceleration publisher
if (publish_acceleration_) {
accel_pub_ =
this->create_publisher<geometry_msgs::msg::AccelWithCovarianceStamped>(
"accel/filtered", rclcpp::QoS(10), publisher_options);
"accel/filtered", rclcpp::QoS(10));
}

const std::chrono::duration<double> timespan{1.0 / frequency_};
Expand Down
7 changes: 3 additions & 4 deletions src/ros_robot_localization_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,12 +75,11 @@ FilterTypes::FilterType filterTypeFromString(
}

RosRobotLocalizationListener::RosRobotLocalizationListener(
rclcpp::Node::SharedPtr node,
rclcpp::SubscriptionOptions options)
rclcpp::Node::SharedPtr node)
: qos1_(1),
qos10_(10),
odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile(), options),
accel_sub_(node, "acceleration/filtered", qos1_.get_rmw_qos_profile(), options),
odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile()),
accel_sub_(node, "acceleration/filtered", qos1_.get_rmw_qos_profile()),
sync_(odom_sub_, accel_sub_, 10u),
node_clock_(node->get_node_clock_interface()->get_clock()),
node_logger_(node->get_node_logging_interface()),
Expand Down

0 comments on commit 3deb91a

Please sign in to comment.