diff --git a/rmf_building_sim_common/src/door_common.cpp b/rmf_building_sim_common/src/door_common.cpp index 729805e..d14df7c 100644 --- a/rmf_building_sim_common/src/door_common.cpp +++ b/rmf_building_sim_common/src/door_common.cpp @@ -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( - "/door_states", rclcpp::SystemDefaultsQoS()); + "sim/door_states", rclcpp::SystemDefaultsQoS()); _door_request_sub = _ros_node->create_subscription( - "/door_requests", rclcpp::SystemDefaultsQoS(), + "sim/door_requests", rclcpp::SystemDefaultsQoS(), [&](DoorRequest::UniquePtr msg) { if (msg->door_name == _state.door_name) diff --git a/rmf_building_sim_common/src/lift_common.cpp b/rmf_building_sim_common/src/lift_common.cpp index fa879cc..d9ca682 100644 --- a/rmf_building_sim_common/src/lift_common.cpp +++ b/rmf_building_sim_common/src/lift_common.cpp @@ -204,13 +204,14 @@ LiftCommon::LiftCommon(rclcpp::Node::SharedPtr node, // initialize pub & sub _lift_state_pub = _ros_node->create_publisher( - "/lift_states", rclcpp::SystemDefaultsQoS()); + "sim/lift_states", rclcpp::SystemDefaultsQoS()); + // TODO(luca) remove adapter door request and make lift command its own doors _door_request_pub = _ros_node->create_publisher( - "/adapter_door_requests", rclcpp::SystemDefaultsQoS()); + "adapter_door_requests", rclcpp::SystemDefaultsQoS()); _lift_request_sub = _ros_node->create_subscription( - "/lift_requests", rclcpp::SystemDefaultsQoS(), + "sim/lift_requests", rclcpp::SystemDefaultsQoS(), [&](LiftRequest::UniquePtr msg) { if (msg->lift_name != _lift_name)