diff --git a/nav2_collision_monitor/CMakeLists.txt b/nav2_collision_monitor/CMakeLists.txt index 8544429466a..2cc7b19c739 100644 --- a/nav2_collision_monitor/CMakeLists.txt +++ b/nav2_collision_monitor/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(tf2_geometry_msgs REQUIRED) find_package(nav2_common REQUIRED) find_package(nav2_util REQUIRED) find_package(nav2_costmap_2d REQUIRED) +find_package(nav2_msgs REQUIRED) ### Header ### @@ -35,6 +36,7 @@ set(dependencies tf2_geometry_msgs nav2_util nav2_costmap_2d + nav2_msgs ) set(executable_name collision_monitor) diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp index 2aed9920d0a..59f151d45d4 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp @@ -28,6 +28,7 @@ #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" +#include "nav2_msgs/msg/collision_monitor_state.hpp" #include "nav2_collision_monitor/types.hpp" #include "nav2_collision_monitor/polygon.hpp" @@ -111,7 +112,8 @@ class CollisionMonitor : public nav2_util::LifecycleNode */ bool getParameters( std::string & cmd_vel_in_topic, - std::string & cmd_vel_out_topic); + std::string & cmd_vel_out_topic, + std::string & state_topic); /** * @brief Supporting routine creating and configuring all polygons * @param base_frame_id Robot base frame ID @@ -174,11 +176,11 @@ class CollisionMonitor : public nav2_util::LifecycleNode Action & robot_action) const; /** - * @brief Prints robot action and polygon caused it (if it was) - * @param robot_action Robot action to print + * @brief Log and publish current robot action and polygon + * @param robot_action Robot action to notify * @param action_polygon Pointer to a polygon causing a selected action */ - void printAction( + void notifyActionState( const Action & robot_action, const std::shared_ptr action_polygon) const; /** @@ -205,6 +207,10 @@ class CollisionMonitor : public nav2_util::LifecycleNode /// @brief Output cmd_vel publisher rclcpp_lifecycle::LifecyclePublisher::SharedPtr cmd_vel_out_pub_; + /// @brief CollisionMonitor state publisher + rclcpp_lifecycle::LifecyclePublisher::SharedPtr + state_pub_; + /// @brief Whether main routine is active bool process_active_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/types.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/types.hpp index aa0b9d729ba..585faeafcb1 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/types.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/types.hpp @@ -15,6 +15,8 @@ #ifndef NAV2_COLLISION_MONITOR__TYPES_HPP_ #define NAV2_COLLISION_MONITOR__TYPES_HPP_ +#include + namespace nav2_collision_monitor { @@ -73,6 +75,7 @@ struct Action { ActionType action_type; Velocity req_vel; + std::string polygon_name; }; } // namespace nav2_collision_monitor diff --git a/nav2_collision_monitor/package.xml b/nav2_collision_monitor/package.xml index 0672683c27e..ae68d62ab67 100644 --- a/nav2_collision_monitor/package.xml +++ b/nav2_collision_monitor/package.xml @@ -20,6 +20,7 @@ nav2_common nav2_util nav2_costmap_2d + nav2_msgs ament_cmake_gtest ament_lint_common diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml index 1b0c36529e7..ac30fc693a5 100644 --- a/nav2_collision_monitor/params/collision_monitor_params.yaml +++ b/nav2_collision_monitor/params/collision_monitor_params.yaml @@ -5,6 +5,7 @@ collision_monitor: odom_frame_id: "odom" cmd_vel_in_topic: "cmd_vel_raw" cmd_vel_out_topic: "cmd_vel" + state_topic: "collision_monitor_state" transform_tolerance: 0.5 source_timeout: 5.0 base_shift_correction: True diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 69523e3c14e..8845cffea41 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -29,7 +29,7 @@ namespace nav2_collision_monitor CollisionMonitor::CollisionMonitor(const rclcpp::NodeOptions & options) : nav2_util::LifecycleNode("collision_monitor", "", options), - process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}}, + process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}, ""}, stop_stamp_{0, 0, get_clock()->get_clock_type()}, stop_pub_timeout_(1.0, 0.0) { } @@ -55,9 +55,10 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/) std::string cmd_vel_in_topic; std::string cmd_vel_out_topic; + std::string state_topic; // Obtaining ROS parameters - if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic)) { + if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, state_topic)) { return nav2_util::CallbackReturn::FAILURE; } @@ -66,6 +67,10 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/) std::bind(&CollisionMonitor::cmdVelInCallback, this, std::placeholders::_1)); cmd_vel_out_pub_ = this->create_publisher( cmd_vel_out_topic, 1); + if (!state_topic.empty()) { + state_pub_ = this->create_publisher( + state_topic, 1); + } return nav2_util::CallbackReturn::SUCCESS; } @@ -77,6 +82,9 @@ CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/) // Activating lifecycle publisher cmd_vel_out_pub_->on_activate(); + if (state_pub_) { + state_pub_->on_activate(); + } // Activating polygons for (std::shared_ptr polygon : polygons_) { @@ -105,7 +113,7 @@ CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/) process_active_ = false; // Reset action type to default after worker deactivating - robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}}; + robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}, ""}; // Deactivating polygons for (std::shared_ptr polygon : polygons_) { @@ -114,6 +122,9 @@ CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // Deactivating lifecycle publishers cmd_vel_out_pub_->on_deactivate(); + if (state_pub_) { + state_pub_->on_deactivate(); + } // Destroying bond connection destroyBond(); @@ -128,6 +139,7 @@ CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/) cmd_vel_in_sub_.reset(); cmd_vel_out_pub_.reset(); + state_pub_.reset(); polygons_.clear(); sources_.clear(); @@ -182,7 +194,8 @@ void CollisionMonitor::publishVelocity(const Action & robot_action) bool CollisionMonitor::getParameters( std::string & cmd_vel_in_topic, - std::string & cmd_vel_out_topic) + std::string & cmd_vel_out_topic, + std::string & state_topic) { std::string base_frame_id, odom_frame_id; tf2::Duration transform_tolerance; @@ -196,6 +209,9 @@ bool CollisionMonitor::getParameters( nav2_util::declare_parameter_if_not_declared( node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel")); cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string(); + nav2_util::declare_parameter_if_not_declared( + node, "state_topic", rclcpp::ParameterValue("")); + state_topic = get_parameter("state_topic").as_string(); nav2_util::declare_parameter_if_not_declared( node, "base_frame_id", rclcpp::ParameterValue("base_footprint")); @@ -359,7 +375,7 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in) } // By default - there is no action - Action robot_action{DO_NOTHING, cmd_vel_in}; + Action robot_action{DO_NOTHING, cmd_vel_in, ""}; // Polygon causing robot action (if any) std::shared_ptr action_polygon; @@ -383,9 +399,9 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in) } } - if (robot_action.action_type != robot_action_prev_.action_type) { + if (robot_action.polygon_name != robot_action_prev_.polygon_name) { // Report changed robot behavior - printAction(robot_action, action_polygon); + notifyActionState(robot_action, action_polygon); } // Publish requred robot velocity @@ -406,6 +422,7 @@ bool CollisionMonitor::processStopSlowdown( if (polygon->getPointsInside(collision_points) > polygon->getMaxPoints()) { if (polygon->getActionType() == STOP) { // Setting up zero velocity for STOP model + robot_action.polygon_name = polygon->getName(); robot_action.action_type = STOP; robot_action.req_vel.x = 0.0; robot_action.req_vel.y = 0.0; @@ -416,6 +433,7 @@ bool CollisionMonitor::processStopSlowdown( // Check that currently calculated velocity is safer than // chosen for previous shapes one if (safe_vel < robot_action.req_vel) { + robot_action.polygon_name = polygon->getName(); robot_action.action_type = SLOWDOWN; robot_action.req_vel = safe_vel; return true; @@ -443,6 +461,7 @@ bool CollisionMonitor::processApproach( // Check that currently calculated velocity is safer than // chosen for previous shapes one if (safe_vel < robot_action.req_vel) { + robot_action.polygon_name = polygon->getName(); robot_action.action_type = APPROACH; robot_action.req_vel = safe_vel; return true; @@ -452,7 +471,7 @@ bool CollisionMonitor::processApproach( return false; } -void CollisionMonitor::printAction( +void CollisionMonitor::notifyActionState( const Action & robot_action, const std::shared_ptr action_polygon) const { if (robot_action.action_type == STOP) { @@ -476,6 +495,15 @@ void CollisionMonitor::printAction( get_logger(), "Robot to continue normal operation"); } + + if (state_pub_) { + std::unique_ptr state_msg = + std::make_unique(); + state_msg->polygon_name = robot_action.polygon_name; + state_msg->action_type = robot_action.action_type; + + state_pub_->publish(std::move(state_msg)); + } } void CollisionMonitor::publishPolygons() const diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index 472530f7865..b6d2ba56735 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -25,6 +25,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_util/lifecycle_node.hpp" +#include "nav2_msgs/msg/collision_monitor_state.hpp" #include "sensor_msgs/msg/laser_scan.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "sensor_msgs/msg/range.hpp" @@ -46,6 +47,7 @@ static const char SOURCE_FRAME_ID[]{"base_source"}; static const char ODOM_FRAME_ID[]{"odom"}; static const char CMD_VEL_IN_TOPIC[]{"cmd_vel_in"}; static const char CMD_VEL_OUT_TOPIC[]{"cmd_vel_out"}; +static const char STATE_TOPIC[]{"collision_monitor_state"}; static const char FOOTPRINT_TOPIC[]{"footprint"}; static const char SCAN_NAME[]{"Scan"}; static const char POINTCLOUD_NAME[]{"PointCloud"}; @@ -73,6 +75,14 @@ enum SourceType RANGE = 3 }; +enum ActionType +{ + DO_NOTHING = 0, + STOP = 1, + SLOWDOWN = 2, + APPROACH = 3, +}; + class CollisionMonitorWrapper : public nav2_collision_monitor::CollisionMonitor { public: @@ -147,9 +157,11 @@ class Tester : public ::testing::Test const std::chrono::nanoseconds & timeout, const rclcpp::Time & stamp); bool waitCmdVel(const std::chrono::nanoseconds & timeout); + bool waitActionState(const std::chrono::nanoseconds & timeout); protected: void cmdVelOutCallback(geometry_msgs::msg::Twist::SharedPtr msg); + void actionStateCallback(nav2_msgs::msg::CollisionMonitorState::SharedPtr msg); // CollisionMonitor node std::shared_ptr cm_; @@ -167,6 +179,11 @@ class Tester : public ::testing::Test rclcpp::Subscription::SharedPtr cmd_vel_out_sub_; geometry_msgs::msg::Twist::SharedPtr cmd_vel_out_; + + // CollisionMonitor Action state + rclcpp::Subscription::SharedPtr action_state_sub_; + nav2_msgs::msg::CollisionMonitorState::SharedPtr action_state_; + }; // Tester Tester::Tester() @@ -188,6 +205,10 @@ Tester::Tester() cmd_vel_out_sub_ = cm_->create_subscription( CMD_VEL_OUT_TOPIC, rclcpp::SystemDefaultsQoS(), std::bind(&Tester::cmdVelOutCallback, this, std::placeholders::_1)); + + action_state_sub_ = cm_->create_subscription( + STATE_TOPIC, rclcpp::SystemDefaultsQoS(), + std::bind(&Tester::actionStateCallback, this, std::placeholders::_1)); } Tester::~Tester() @@ -201,6 +222,8 @@ Tester::~Tester() cmd_vel_in_pub_.reset(); cmd_vel_out_sub_.reset(); + action_state_sub_.reset(); + cm_.reset(); } @@ -214,6 +237,10 @@ void Tester::setCommonParameters() "cmd_vel_out_topic", rclcpp::ParameterValue(CMD_VEL_OUT_TOPIC)); cm_->set_parameter( rclcpp::Parameter("cmd_vel_out_topic", CMD_VEL_OUT_TOPIC)); + cm_->declare_parameter( + "state_topic", rclcpp::ParameterValue(STATE_TOPIC)); + cm_->set_parameter( + rclcpp::Parameter("state_topic", STATE_TOPIC)); cm_->declare_parameter( "base_frame_id", rclcpp::ParameterValue(BASE_FRAME_ID)); @@ -499,6 +526,7 @@ void Tester::publishCmdVel(const double x, const double y, const double tw) { // Reset cmd_vel_out_ before calling CollisionMonitor::process() cmd_vel_out_ = nullptr; + action_state_ = nullptr; std::unique_ptr msg = std::make_unique(); @@ -539,11 +567,29 @@ bool Tester::waitCmdVel(const std::chrono::nanoseconds & timeout) return false; } +bool Tester::waitActionState(const std::chrono::nanoseconds & timeout) +{ + rclcpp::Time start_time = cm_->now(); + while (rclcpp::ok() && cm_->now() - start_time <= rclcpp::Duration(timeout)) { + if (action_state_) { + return true; + } + rclcpp::spin_some(cm_->get_node_base_interface()); + std::this_thread::sleep_for(10ms); + } + return false; +} + void Tester::cmdVelOutCallback(geometry_msgs::msg::Twist::SharedPtr msg) { cmd_vel_out_ = msg; } +void Tester::actionStateCallback(nav2_msgs::msg::CollisionMonitorState::SharedPtr msg) +{ + action_state_ = msg; +} + TEST_F(Tester, testProcessStopSlowdown) { rclcpp::Time curr_time = cm_->now(); @@ -579,6 +625,9 @@ TEST_F(Tester, testProcessStopSlowdown) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5 * SLOWDOWN_RATIO, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2 * SLOWDOWN_RATIO, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1 * SLOWDOWN_RATIO, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, SLOWDOWN); + ASSERT_EQ(action_state_->polygon_name, "SlowDown"); // 3. Obstacle is inside stop zone publishScan(0.5, curr_time); @@ -588,6 +637,9 @@ TEST_F(Tester, testProcessStopSlowdown) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, STOP); + ASSERT_EQ(action_state_->polygon_name, "Stop"); // 4. Restoring back normal operation publishScan(3.0, curr_time); @@ -597,6 +649,9 @@ TEST_F(Tester, testProcessStopSlowdown) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); // Stop Collision Monitor node cm_->stop(); @@ -641,6 +696,9 @@ TEST_F(Tester, testProcessApproach) ASSERT_NEAR( cmd_vel_out_->linear.y, 0.2 * change_ratio, 0.2 * SIMULATION_TIME_STEP / TIME_BEFORE_COLLISION); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, APPROACH); + ASSERT_EQ(action_state_->polygon_name, "Approach"); // 3. Obstacle is inside robot footprint publishScan(0.5, curr_time); @@ -659,6 +717,9 @@ TEST_F(Tester, testProcessApproach) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); // Stop Collision Monitor node cm_->stop(); @@ -706,6 +767,9 @@ TEST_F(Tester, testProcessApproachRotation) cmd_vel_out_->angular.z, M_PI / 5, (M_PI / 4) * (SIMULATION_TIME_STEP / TIME_BEFORE_COLLISION)); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, APPROACH); + ASSERT_EQ(action_state_->polygon_name, "Approach"); // 3. Obstacle is inside robot footprint publishRange(0.5, curr_time); @@ -724,6 +788,9 @@ TEST_F(Tester, testProcessApproachRotation) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, M_PI / 4, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); // Stop Collision Monitor node cm_->stop(); @@ -761,6 +828,9 @@ TEST_F(Tester, testCrossOver) cmd_vel_out_->linear.x, 3.0 * change_ratio, 3.0 * SIMULATION_TIME_STEP / TIME_BEFORE_COLLISION); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, APPROACH); + ASSERT_EQ(action_state_->polygon_name, "Approach"); // 2. Obstacle is inside slowdown zone, but speed is too slow for approach publishRange(1.5, curr_time); @@ -770,6 +840,9 @@ TEST_F(Tester, testCrossOver) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.1 * SLOWDOWN_RATIO, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, SLOWDOWN); + ASSERT_EQ(action_state_->polygon_name, "SlowDown"); // 3. Increase robot speed to return again into approach mode. // The speed should be safer for approach mode, so robot will go to the approach (ahead in 0.5 m) @@ -782,6 +855,9 @@ TEST_F(Tester, testCrossOver) cmd_vel_out_->linear.x, 1.0 * change_ratio, 1.0 * SIMULATION_TIME_STEP / TIME_BEFORE_COLLISION); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, APPROACH); + ASSERT_EQ(action_state_->polygon_name, "Approach"); // Stop Collision Monitor node cm_->stop(); @@ -812,6 +888,9 @@ TEST_F(Tester, testCeasePublishZeroVel) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, APPROACH); + ASSERT_EQ(action_state_->polygon_name, "Approach"); // Wait more than STOP_PUB_TIMEOUT time std::this_thread::sleep_for(std::chrono::duration(STOP_PUB_TIMEOUT + 0.01)); @@ -828,6 +907,9 @@ TEST_F(Tester, testCeasePublishZeroVel) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, DO_NOTHING); + ASSERT_EQ(action_state_->polygon_name, ""); // 4. Obstacle is inside stop zone publishScan(0.5, curr_time); @@ -837,6 +919,9 @@ TEST_F(Tester, testCeasePublishZeroVel) ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON); ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON); + ASSERT_TRUE(waitActionState(500ms)); + ASSERT_EQ(action_state_->action_type, STOP); + ASSERT_EQ(action_state_->polygon_name, "Stop"); // Wait more than STOP_PUB_TIMEOUT time std::this_thread::sleep_for(std::chrono::duration(STOP_PUB_TIMEOUT + 0.01)); diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt index 2be81db0a74..eff2bf352a7 100644 --- a/nav2_msgs/CMakeLists.txt +++ b/nav2_msgs/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(action_msgs REQUIRED) nav2_package() rosidl_generate_interfaces(${PROJECT_NAME} + "msg/CollisionMonitorState.msg" "msg/Costmap.msg" "msg/CostmapMetaData.msg" "msg/CostmapFilterInfo.msg" diff --git a/nav2_msgs/msg/CollisionMonitorState.msg b/nav2_msgs/msg/CollisionMonitorState.msg new file mode 100644 index 00000000000..493fc3c03d7 --- /dev/null +++ b/nav2_msgs/msg/CollisionMonitorState.msg @@ -0,0 +1,9 @@ +# Action type for robot in Collision Monitor +uint8 DO_NOTHING=0 # No action +uint8 STOP=1 # Stop the robot +uint8 SLOWDOWN=2 # Slowdown in percentage from current operating speed +uint8 APPROACH=3 # Keep constant time interval before collision +uint8 action_type + +# Name of triggered polygon +string polygon_name