diff --git a/rmf_robot_sim_common/include/rmf_robot_sim_common/slotcar_common.hpp b/rmf_robot_sim_common/include/rmf_robot_sim_common/slotcar_common.hpp index 59977c4..96e3ab7 100644 --- a/rmf_robot_sim_common/include/rmf_robot_sim_common/slotcar_common.hpp +++ b/rmf_robot_sim_common/include/rmf_robot_sim_common/slotcar_common.hpp @@ -25,6 +25,7 @@ #include #include +#include #include #include #include @@ -174,6 +175,7 @@ class SlotcarCommon std::shared_ptr _tf2_broadcaster; rclcpp::Publisher::SharedPtr _robot_state_pub; + rclcpp::Publisher::SharedPtr _collision_pub; rclcpp::Subscription::SharedPtr _traj_sub; rclcpp::Subscription::SharedPtr _pause_sub; diff --git a/rmf_robot_sim_common/src/slotcar_common.cpp b/rmf_robot_sim_common/src/slotcar_common.cpp index b2cf67a..ce3036c 100644 --- a/rmf_robot_sim_common/src/slotcar_common.cpp +++ b/rmf_robot_sim_common/src/slotcar_common.cpp @@ -211,6 +211,10 @@ void SlotcarCommon::init_ros_node(const rclcpp::Node::SharedPtr node) _ros_node->create_publisher( "/robot_state", 10); + _collision_pub = + _ros_node->create_publisher( + "/robot_collisions", 10); + auto qos_profile = rclcpp::QoS(10); qos_profile.transient_local(); _building_map_sub = @@ -842,8 +846,25 @@ bool SlotcarCommon::emergency_stop( // TODO flush logger here // TODO get collision object name if (need_to_stop) + { RCLCPP_INFO_STREAM(logger(), "Stopping [" << _model_name << "] to avoid a collision"); + + rmf_fleet_msgs::msg::RobotCollision msg; + msg.robot_name = _model_name; + + msg.location.t = _ros_node->get_clock()->now(); + msg.location.x = _pose.translation()[0]; + msg.location.y = _pose.translation()[1]; + msg.location.yaw = compute_yaw(_pose); + msg.location.level_name = get_level_name(_pose.translation()[2]); + if (!_remaining_path.empty()) + { + msg.location.index = _remaining_path.front().index; + } + + _collision_pub->publish(msg); + } else RCLCPP_INFO_STREAM(logger(), "No more obstacles; resuming course for [" << _model_name << "]");