Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Planning Scene Monitor should use relaible QoS with >1 history #3257

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@

/* Author: Ioan Sucan */

#include <rclcpp/qos.hpp>

#include <moveit/planning_scene_monitor/planning_scene_monitor.hpp>
#include <moveit/robot_model_loader/robot_model_loader.hpp>
#include <moveit/utils/message_checks.hpp>
Expand Down Expand Up @@ -1176,8 +1178,12 @@ void PlanningSceneMonitor::startSceneMonitor(const std::string& scene_topic)
// listen for planning scene updates; these messages include transforms, so no need for filters
if (!scene_topic.empty())
{
// Missing even a single message may result in wrong state of attached objects, need to have reliable QoS
// with a sufficient queue length
rclcpp::QoS qos(10);
qos.reliable();
planning_scene_subscriber_ = pnode_->create_subscription<moveit_msgs::msg::PlanningScene>(
scene_topic, rclcpp::SystemDefaultsQoS(), [this](const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene) {
scene_topic, qos, [this](const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene) {
Copy link
Contributor

@rhaschke rhaschke Jan 22, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

According to the docs, the default profile for publishers/subscribers already matches the desired settings.
Hence, it should be sufficient to use that profile instead of rclcpp::SystemDefaultsQoS():

- scene_topic, rclcpp::SystemDefaultsQoS(), [this](const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene) {
+ scene_topic, rmw_qos_profile_default, [this](const moveit_msgs::msg::PlanningScene::ConstSharedPtr& scene) {

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actually, rclcpp::SystemDefaultsQoS() should not be used anywhere in the code. Instead, the profiles predefined for specific use cases should be used.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No clue how things are supposed to work, but what I saw reported by ros2 topic info was that the subscription was "Reliability: BEST_EFFORT" with queue size of 1. That said, I am a novice in ROS2, so if there is an easier way to specify the desired QoS, I do not know.

return newPlanningSceneCallback(scene);
});
RCLCPP_INFO(logger_, "Listening to '%s'", planning_scene_subscriber_->get_topic_name());
Expand Down
Loading