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

Explicitly specify all qos depth #70

Merged
merged 5 commits into from
Feb 1, 2024
Merged
Show file tree
Hide file tree
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
2 changes: 1 addition & 1 deletion rmf_visualization_floorplans/src/FloorplanVisualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ FloorplanVisualizer::FloorplanVisualizer(const rclcpp::NodeOptions& options)

_param_sub = this->create_subscription<RvizParam>(
"rmf_visualization/parameters",
rclcpp::SystemDefaultsQoS(),
rclcpp::SystemDefaultsQoS().keep_last(10),
[=](RvizParam::ConstSharedPtr msg)
{
if (msg->map_name.empty() || msg->map_name == _current_level)
Expand Down
2 changes: 1 addition & 1 deletion rmf_visualization_navgraphs/src/NavGraphVisualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,7 +411,7 @@ NavGraphVisualizer::NavGraphVisualizer(const rclcpp::NodeOptions& options)
// It is okay to capture this by reference here.
_param_sub = this->create_subscription<RvizParam>(
"rmf_visualization/parameters",
rclcpp::SystemDefaultsQoS(),
rclcpp::SystemDefaultsQoS().keep_last(10),
[=](RvizParam::ConstSharedPtr msg)
{
if (msg->map_name.empty() || msg->map_name == _current_level)
Expand Down
8 changes: 3 additions & 5 deletions rmf_visualization_rviz2_plugins/src/LiftPanel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<LiftRequest>(
LiftRequestTopicName, transient_qos);
LiftRequestTopicName, rclcpp::QoS(10));
_adapter_lift_request_pub = _node->create_publisher<LiftRequest>(
AdapterLiftRequestTopicName, transient_qos);
AdapterLiftRequestTopicName, rclcpp::QoS(10));

create_layout();
create_connections();
Expand Down Expand Up @@ -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 = "";
Expand Down
13 changes: 8 additions & 5 deletions rmf_visualization_rviz2_plugins/src/SchedulePanel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,9 +42,10 @@ SchedulePanel::SchedulePanel(QWidget* parent)

// Creating publisher
_param_pub = _node->create_publisher<RvizParamMsg>(
_param_topic.toStdString(), rclcpp::SystemDefaultsQoS());
_param_topic.toStdString(), rclcpp::SystemDefaultsQoS().keep_last(10));
_cancel_pub = _node->create_publisher<NegotiationRefusal>(
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;
Expand Down Expand Up @@ -130,14 +131,16 @@ SchedulePanel::SchedulePanel(QWidget* parent)
SIGNAL(clicked()), this, SLOT(cancel_negotiation()));

_notice_sub = _node->create_subscription<NegotiationNotice>(
"/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<NegotiationConclusion>(
"/rmf_traffic/negotiation_conclusion", rclcpp::SystemDefaultsQoS(),
"/rmf_traffic/negotiation_conclusion", rclcpp::SystemDefaultsQoS().keep_last(
10),
[&](const NegotiationConclusion::UniquePtr msg)
{
this->recieved_conclusion(*msg);
Expand Down Expand Up @@ -263,7 +266,7 @@ void SchedulePanel::set_topic(const QString& new_topic)
{
// Update publisher
_param_pub = _node->create_publisher<RvizParamMsg>(
_param_topic.toStdString(), rclcpp::SystemDefaultsQoS());
_param_topic.toStdString(), rclcpp::SystemDefaultsQoS().keep_last(10));
// Send new message
send_param();
}
Expand Down
Loading