diff --git a/rmf_visualization_floorplans/src/FloorplanVisualizer.cpp b/rmf_visualization_floorplans/src/FloorplanVisualizer.cpp index d27cd4c..e0eefa6 100644 --- a/rmf_visualization_floorplans/src/FloorplanVisualizer.cpp +++ b/rmf_visualization_floorplans/src/FloorplanVisualizer.cpp @@ -123,7 +123,7 @@ FloorplanVisualizer::FloorplanVisualizer(const rclcpp::NodeOptions& options) _param_sub = this->create_subscription( "rmf_visualization/parameters", - rclcpp::SystemDefaultsQoS(), + rclcpp::SystemDefaultsQoS().keep_last(10), [=](RvizParam::ConstSharedPtr msg) { if (msg->map_name.empty() || msg->map_name == _current_level) diff --git a/rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp b/rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp index 8ce7438..4eee6cc 100644 --- a/rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp +++ b/rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp @@ -411,7 +411,7 @@ NavGraphVisualizer::NavGraphVisualizer(const rclcpp::NodeOptions& options) // It is okay to capture this by reference here. _param_sub = this->create_subscription( "rmf_visualization/parameters", - rclcpp::SystemDefaultsQoS(), + rclcpp::SystemDefaultsQoS().keep_last(10), [=](RvizParam::ConstSharedPtr msg) { if (msg->map_name.empty() || msg->map_name == _current_level) diff --git a/rmf_visualization_rviz2_plugins/src/LiftPanel.cpp b/rmf_visualization_rviz2_plugins/src/LiftPanel.cpp index 3b10ce8..7779c17 100644 --- a/rmf_visualization_rviz2_plugins/src/LiftPanel.cpp +++ b/rmf_visualization_rviz2_plugins/src/LiftPanel.cpp @@ -36,12 +36,10 @@ LiftPanel::LiftPanel(QWidget* parent) { lift_state_callback(std::move(msg)); }); - const auto transient_qos = rclcpp::SystemDefaultsQoS() - .reliable().keep_last(100).transient_local(); _lift_request_pub = _node->create_publisher( - LiftRequestTopicName, transient_qos); + LiftRequestTopicName, rclcpp::QoS(10)); _adapter_lift_request_pub = _node->create_publisher( - AdapterLiftRequestTopicName, transient_qos); + AdapterLiftRequestTopicName, rclcpp::QoS(10)); create_layout(); create_connections(); @@ -375,7 +373,7 @@ void LiftPanel::lift_state_callback(LiftState::UniquePtr msg) void LiftPanel::display_state(const LiftState& msg) { std::string floors_str = ""; - for (const auto& f : msg.available_floors) + for (const auto f : msg.available_floors) floors_str += f + ", "; std::string available_modes_str = ""; diff --git a/rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp b/rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp index 332c560..f47585f 100644 --- a/rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp +++ b/rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp @@ -42,9 +42,10 @@ SchedulePanel::SchedulePanel(QWidget* parent) // Creating publisher _param_pub = _node->create_publisher( - _param_topic.toStdString(), rclcpp::SystemDefaultsQoS()); + _param_topic.toStdString(), rclcpp::SystemDefaultsQoS().keep_last(10)); _cancel_pub = _node->create_publisher( - rmf_traffic_ros2::NegotiationRefusalTopicName, rclcpp::SystemDefaultsQoS()); + rmf_traffic_ros2::NegotiationRefusalTopicName, + rclcpp::SystemDefaultsQoS().keep_last(10)); // Create layout for output topic and map_name QHBoxLayout* layout1 = new QHBoxLayout; @@ -130,14 +131,16 @@ SchedulePanel::SchedulePanel(QWidget* parent) SIGNAL(clicked()), this, SLOT(cancel_negotiation())); _notice_sub = _node->create_subscription( - "/rmf_traffic/negotiation_notice", rclcpp::SystemDefaultsQoS(), + "/rmf_traffic/negotiation_notice", rclcpp::SystemDefaultsQoS().keep_last( + 10), [&](const NegotiationNotice::UniquePtr msg) { this->recieved_notification(*msg); }); _conclusion_sub = _node->create_subscription( - "/rmf_traffic/negotiation_conclusion", rclcpp::SystemDefaultsQoS(), + "/rmf_traffic/negotiation_conclusion", rclcpp::SystemDefaultsQoS().keep_last( + 10), [&](const NegotiationConclusion::UniquePtr msg) { this->recieved_conclusion(*msg); @@ -263,7 +266,7 @@ void SchedulePanel::set_topic(const QString& new_topic) { // Update publisher _param_pub = _node->create_publisher( - _param_topic.toStdString(), rclcpp::SystemDefaultsQoS()); + _param_topic.toStdString(), rclcpp::SystemDefaultsQoS().keep_last(10)); // Send new message send_param(); }