15 #ifndef NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
16 #define NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
21 #include <unordered_map>
23 #include "rclcpp/rclcpp.hpp"
24 #include "geometry_msgs/msg/twist.hpp"
25 #include "visualization_msgs/msg/marker_array.hpp"
26 #include "geometry_msgs/msg/twist_stamped.hpp"
29 #include "tf2_ros/buffer.h"
30 #include "tf2_ros/transform_listener.h"
32 #include "nav2_util/lifecycle_node.hpp"
33 #include "nav2_util/twist_publisher.hpp"
34 #include "nav2_util/twist_subscriber.hpp"
35 #include "nav2_msgs/msg/collision_monitor_state.hpp"
37 #include "nav2_collision_monitor/types.hpp"
38 #include "nav2_collision_monitor/polygon.hpp"
39 #include "nav2_collision_monitor/circle.hpp"
40 #include "nav2_collision_monitor/velocity_polygon.hpp"
41 #include "nav2_collision_monitor/source.hpp"
42 #include "nav2_collision_monitor/scan.hpp"
43 #include "nav2_collision_monitor/pointcloud.hpp"
44 #include "nav2_collision_monitor/range.hpp"
45 #include "nav2_collision_monitor/polygon_source.hpp"
47 namespace nav2_collision_monitor
60 explicit CollisionMonitor(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
73 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
79 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
85 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
91 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
97 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
105 void cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg);
123 std::string & cmd_vel_in_topic,
124 std::string & cmd_vel_out_topic,
125 std::string & state_topic);
133 const std::string & base_frame_id,
134 const tf2::Duration & transform_tolerance);
147 const std::string & base_frame_id,
148 const std::string & odom_frame_id,
149 const tf2::Duration & transform_tolerance,
150 const rclcpp::Duration & source_timeout,
151 const bool base_shift_correction);
158 void process(
const Velocity & cmd_vel_in,
const std_msgs::msg::Header & header);
170 const std::shared_ptr<Polygon> polygon,
171 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
173 Action & robot_action)
const;
185 const std::shared_ptr<Polygon> polygon,
186 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
188 Action & robot_action)
const;
196 const Action & robot_action,
const std::shared_ptr<Polygon> action_polygon)
const;
223 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CollisionMonitorState>::SharedPtr
227 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
Collision Monitor ROS2 node.
std::unique_ptr< nav2_util::TwistSubscriber > cmd_vel_in_sub_
Input cmd_vel subscriber.
rclcpp_lifecycle::LifecyclePublisher< nav2_msgs::msg::CollisionMonitorState >::SharedPtr state_pub_
CollisionMonitor state publisher.
void notifyActionState(const Action &robot_action, const std::shared_ptr< Polygon > action_polygon) const
Log and publish current robot action and polygon.
std::unique_ptr< nav2_util::TwistPublisher > cmd_vel_out_pub_
Output cmd_vel publisher.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates LifecyclePublishers, polygons and main processor, creates bond connection
Action robot_action_prev_
Previous robot action.
rclcpp::Duration stop_pub_timeout_
Timeout after which 0-velocity ceases to be published.
bool process_active_
Whether main routine is active.
bool configurePolygons(const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
Supporting routine creating and configuring all polygons.
std::vector< std::shared_ptr< Polygon > > polygons_
Polygons array.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
~CollisionMonitor()
Destructor for the nav2_collision_monitor::CollisionMonitor.
bool processApproach(const std::shared_ptr< Polygon > polygon, const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity, Action &robot_action) const
Processes APPROACH action type.
rclcpp::Time stop_stamp_
Latest timestamp when robot has 0-velocity.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all subscribers/publishers, polygons/data sources arrays
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection
std::vector< std::shared_ptr< Source > > sources_
Data sources array.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes and obtains ROS-parameters, creates main subscribers and publishers,...
bool getParameters(std::string &cmd_vel_in_topic, std::string &cmd_vel_out_topic, std::string &state_topic)
Supporting routine obtaining all ROS-parameters.
CollisionMonitor(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_monitor::CollisionMonitor.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
void cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg)
Callback for input cmd_vel.
bool configureSources(const std::string &base_frame_id, const std::string &odom_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)
Supporting routine creating and configuring all data sources.
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
Collision points marker publisher.
void process(const Velocity &cmd_vel_in, const std_msgs::msg::Header &header)
Main processing routine.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
void publishVelocity(const Action &robot_action, const std_msgs::msg::Header &header)
Publishes output cmd_vel. If robot was stopped more than stop_pub_timeout_ seconds,...
bool processStopSlowdownLimit(const std::shared_ptr< Polygon > polygon, const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity, Action &robot_action) const
Processes the polygon of STOP, SLOWDOWN and LIMIT action type.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
Velocity for 2D model of motion.