Skip to content

Commit

Permalink
add qos overrides for finders (#174)
Browse files Browse the repository at this point in the history
this is primarily a workaround for the issues seen
in jazzy where large topics do not come through
over best effort subscribers.
  • Loading branch information
mikeferguson authored Sep 26, 2024
1 parent 91144a5 commit fca5e64
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 4 deletions.
5 changes: 4 additions & 1 deletion robot_calibration/src/finders/checkerboard_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,13 @@ bool CheckerboardFinder<T>::init(const std::string& name,
// Setup subscriber
std::string topic_name;
topic_name = node->declare_parameter<std::string>(name + ".topic", name + "/points");
rclcpp::SubscriptionOptions options;
options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
subscriber_ = node->create_subscription<T>(
topic_name,
rclcpp::QoS(1).best_effort().keep_last(1),
std::bind(&CheckerboardFinder::cameraCallback, this, std::placeholders::_1));
std::bind(&CheckerboardFinder::cameraCallback, this, std::placeholders::_1),
options);

// Size of checkerboard
points_x_ = node->declare_parameter<int>(name + ".points_x", 5);
Expand Down
5 changes: 4 additions & 1 deletion robot_calibration/src/finders/led_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,10 +69,13 @@ bool LedFinder::init(const std::string& name,

// Setup subscriber
topic_name = node->declare_parameter<std::string>(name + ".topic", name + "/points");
rclcpp::SubscriptionOptions options;
options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
subscriber_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
topic_name,
rclcpp::QoS(1).best_effort(),
std::bind(&LedFinder::cameraCallback, this, std::placeholders::_1));
std::bind(&LedFinder::cameraCallback, this, std::placeholders::_1),
options);

// Publish where LEDs were seen
publisher_ = node->create_publisher<sensor_msgs::msg::PointCloud2>(name + "_points", 10);
Expand Down
5 changes: 4 additions & 1 deletion robot_calibration/src/finders/plane_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,10 +106,13 @@ bool PlaneFinder::init(const std::string& name,
// We subscribe to a PointCloud2
std::string topic_name =
node->declare_parameter<std::string>(name + ".topic", name + "/points");
rclcpp::SubscriptionOptions options;
options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
subscriber_ = node->create_subscription<sensor_msgs::msg::PointCloud2>(
topic_name,
rclcpp::QoS(1).best_effort(),
std::bind(&PlaneFinder::cameraCallback, this, std::placeholders::_1));
std::bind(&PlaneFinder::cameraCallback, this, std::placeholders::_1),
options);

// Name of the sensor model that will be used during optimization
plane_sensor_name_ = node->declare_parameter<std::string>(name + ".camera_sensor_name", "camera");
Expand Down
5 changes: 4 additions & 1 deletion robot_calibration/src/finders/scan_finder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,13 @@ bool ScanFinder::init(const std::string& name,
// We subscribe to a LaserScan
std::string topic_name;
topic_name = node->declare_parameter<std::string>(name + ".topic", name + "/scan");
rclcpp::SubscriptionOptions options;
options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();
subscriber_ = node->create_subscription<sensor_msgs::msg::LaserScan>(
topic_name,
rclcpp::QoS(1).best_effort(),
std::bind(&ScanFinder::scanCallback, this, std::placeholders::_1));
std::bind(&ScanFinder::scanCallback, this, std::placeholders::_1),
options);

// Name of the sensor model that will be used during optimization
laser_sensor_name_ = node->declare_parameter<std::string>(name + ".sensor_name", "laser");
Expand Down

0 comments on commit fca5e64

Please sign in to comment.