Skip to content

Commit f71d2d3

Browse files
author
Teo Koon Peng
authored
Explicitly specify all qos depth (#116)
1 parent c985ed0 commit f71d2d3

File tree

5 files changed

+11
-11
lines changed

5 files changed

+11
-11
lines changed

rmf_building_sim_common/src/door_common.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -72,10 +72,10 @@ DoorCommon::DoorCommon(const std::string& door_name,
7272
_request.requested_mode.value = DoorMode::MODE_CLOSED;
7373

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

7777
_door_request_sub = _ros_node->create_subscription<DoorRequest>(
78-
"/door_requests", rclcpp::SystemDefaultsQoS(),
78+
"/door_requests", rclcpp::SystemDefaultsQoS().keep_last(10),
7979
[&](DoorRequest::UniquePtr msg)
8080
{
8181
if (msg->door_name == _state.door_name)

rmf_building_sim_common/src/lift_common.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -204,13 +204,13 @@ LiftCommon::LiftCommon(rclcpp::Node::SharedPtr node,
204204

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

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

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

249249
_door_state_sub = _ros_node->create_subscription<DoorState>(
250-
"/door_states", rclcpp::SystemDefaultsQoS(),
250+
"/door_states", rclcpp::SystemDefaultsQoS().keep_last(10),
251251
[&](DoorState::SharedPtr msg)
252252
{
253253
std::string name = msg->door_name;

rmf_building_sim_gz_classic_plugins/src/toggle_floors.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class ToggleFloors : public gazebo::GUIPlugin
5151

5252
// toggle non-static robots
5353
fleet_state_sub = ros_node->create_subscription<FleetState>(
54-
"/fleet_states", rclcpp::SystemDefaultsQoS(),
54+
"/fleet_states", rclcpp::SystemDefaultsQoS().keep_last(10),
5555
[&](FleetState::UniquePtr msg)
5656
{
5757
bool visible;

rmf_robot_sim_common/src/dispenser_common.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@ void TeleportDispenserCommon::init_ros_node(const rclcpp::Node::SharedPtr node)
187187

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

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

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

rmf_robot_sim_common/src/ingestor_common.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ void TeleportIngestorCommon::init_ros_node(const rclcpp::Node::SharedPtr node)
182182

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

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

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

0 commit comments

Comments
 (0)