Skip to content

Commit

Permalink
Explicitly specify all qos depth (#116)
Browse files Browse the repository at this point in the history
  • Loading branch information
Teo Koon Peng committed Feb 1, 2024
1 parent c985ed0 commit f71d2d3
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 11 deletions.
4 changes: 2 additions & 2 deletions rmf_building_sim_common/src/door_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,10 +72,10 @@ DoorCommon::DoorCommon(const std::string& door_name,
_request.requested_mode.value = DoorMode::MODE_CLOSED;

_door_state_pub = _ros_node->create_publisher<DoorState>(
"/door_states", rclcpp::SystemDefaultsQoS());
"/door_states", rclcpp::SystemDefaultsQoS().keep_last(10));

_door_request_sub = _ros_node->create_subscription<DoorRequest>(
"/door_requests", rclcpp::SystemDefaultsQoS(),
"/door_requests", rclcpp::SystemDefaultsQoS().keep_last(10),
[&](DoorRequest::UniquePtr msg)
{
if (msg->door_name == _state.door_name)
Expand Down
8 changes: 4 additions & 4 deletions rmf_building_sim_common/src/lift_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,13 +204,13 @@ LiftCommon::LiftCommon(rclcpp::Node::SharedPtr node,

// initialize pub & sub
_lift_state_pub = _ros_node->create_publisher<LiftState>(
"/lift_states", rclcpp::SystemDefaultsQoS());
"/lift_states", rclcpp::SystemDefaultsQoS().keep_last(10));

_door_request_pub = _ros_node->create_publisher<DoorRequest>(
"/adapter_door_requests", rclcpp::SystemDefaultsQoS());
"/adapter_door_requests", rclcpp::SystemDefaultsQoS().keep_last(10));

_lift_request_sub = _ros_node->create_subscription<LiftRequest>(
"/lift_requests", rclcpp::SystemDefaultsQoS(),
"/lift_requests", rclcpp::SystemDefaultsQoS().keep_last(10),
[&](LiftRequest::UniquePtr msg)
{
if (msg->lift_name != _lift_name)
Expand Down Expand Up @@ -247,7 +247,7 @@ LiftCommon::LiftCommon(rclcpp::Node::SharedPtr node,
});

_door_state_sub = _ros_node->create_subscription<DoorState>(
"/door_states", rclcpp::SystemDefaultsQoS(),
"/door_states", rclcpp::SystemDefaultsQoS().keep_last(10),
[&](DoorState::SharedPtr msg)
{
std::string name = msg->door_name;
Expand Down
2 changes: 1 addition & 1 deletion rmf_building_sim_gz_classic_plugins/src/toggle_floors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class ToggleFloors : public gazebo::GUIPlugin

// toggle non-static robots
fleet_state_sub = ros_node->create_subscription<FleetState>(
"/fleet_states", rclcpp::SystemDefaultsQoS(),
"/fleet_states", rclcpp::SystemDefaultsQoS().keep_last(10),
[&](FleetState::UniquePtr msg)
{
bool visible;
Expand Down
4 changes: 2 additions & 2 deletions rmf_robot_sim_common/src/dispenser_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ void TeleportDispenserCommon::init_ros_node(const rclcpp::Node::SharedPtr node)

_fleet_state_sub = ros_node->create_subscription<FleetState>(
"/fleet_states",
rclcpp::SystemDefaultsQoS(),
rclcpp::SystemDefaultsQoS().keep_last(10),
std::bind(&TeleportDispenserCommon::fleet_state_cb, this,
std::placeholders::_1));

Expand All @@ -196,7 +196,7 @@ void TeleportDispenserCommon::init_ros_node(const rclcpp::Node::SharedPtr node)

_request_sub = ros_node->create_subscription<DispenserRequest>(
"/dispenser_requests",
rclcpp::SystemDefaultsQoS().reliable(),
rclcpp::SystemDefaultsQoS().keep_last(10).reliable(),
std::bind(&TeleportDispenserCommon::dispenser_request_cb, this,
std::placeholders::_1));

Expand Down
4 changes: 2 additions & 2 deletions rmf_robot_sim_common/src/ingestor_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ void TeleportIngestorCommon::init_ros_node(const rclcpp::Node::SharedPtr node)

_fleet_state_sub = ros_node->create_subscription<FleetState>(
"/fleet_states",
rclcpp::SystemDefaultsQoS(),
rclcpp::SystemDefaultsQoS().keep_last(10),
std::bind(&TeleportIngestorCommon::fleet_state_cb, this,
std::placeholders::_1));

Expand All @@ -191,7 +191,7 @@ void TeleportIngestorCommon::init_ros_node(const rclcpp::Node::SharedPtr node)

_request_sub = ros_node->create_subscription<IngestorRequest>(
"/ingestor_requests",
rclcpp::SystemDefaultsQoS().reliable(),
rclcpp::SystemDefaultsQoS().keep_last(10).reliable(),
std::bind(&TeleportIngestorCommon::ingestor_request_cb, this,
std::placeholders::_1));

Expand Down

0 comments on commit f71d2d3

Please sign in to comment.