16 #ifndef NAV2_COLLISION_MONITOR__COLLISION_DETECTOR_NODE_HPP_
17 #define NAV2_COLLISION_MONITOR__COLLISION_DETECTOR_NODE_HPP_
23 #include "rclcpp/rclcpp.hpp"
25 #include "tf2/time.hpp"
26 #include "tf2_ros/buffer.h"
27 #include "tf2_ros/transform_listener.h"
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "nav2_msgs/msg/collision_detector_state.hpp"
31 #include "visualization_msgs/msg/marker_array.hpp"
33 #include "nav2_collision_monitor/types.hpp"
34 #include "nav2_collision_monitor/polygon.hpp"
35 #include "nav2_collision_monitor/circle.hpp"
36 #include "nav2_collision_monitor/velocity_polygon.hpp"
37 #include "nav2_collision_monitor/source.hpp"
38 #include "nav2_collision_monitor/scan.hpp"
39 #include "nav2_collision_monitor/pointcloud.hpp"
40 #include "nav2_collision_monitor/range.hpp"
41 #include "nav2_collision_monitor/polygon_source.hpp"
43 namespace nav2_collision_monitor
56 explicit CollisionDetector(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
69 nav2_util::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
75 nav2_util::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
81 nav2_util::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
87 nav2_util::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
93 nav2_util::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
108 const std::string & base_frame_id,
109 const tf2::Duration & transform_tolerance);
122 const std::string & base_frame_id,
123 const std::string & odom_frame_id,
124 const tf2::Duration & transform_tolerance,
125 const rclcpp::Duration & source_timeout,
126 const bool base_shift_correction);
151 rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CollisionDetectorState>::SharedPtr
154 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
Collision Monitor ROS2 node.
bool getParameters()
Supporting routine obtaining all ROS-parameters.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all subscribers/publishers, polygons/data sources arrays
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.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates LifecyclePublishers, polygons and main processor, creates bond connection
void process()
Main processing routine.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection
~CollisionDetector()
Destructor for the nav2_collision_monitor::CollisionDetector.
rclcpp_lifecycle::LifecyclePublisher< nav2_msgs::msg::CollisionDetectorState >::SharedPtr state_pub_
collision monitor state publisher
std::vector< std::shared_ptr< Source > > sources_
Data sources array.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
bool configurePolygons(const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
Supporting routine creating and configuring all polygons.
rclcpp::TimerBase::SharedPtr timer_
timer that runs actions
double frequency_
main loop frequency
std::vector< std::shared_ptr< Polygon > > polygons_
Polygons array.
CollisionDetector(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_monitor::CollisionDetector.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes and obtains ROS-parameters, creates main subscribers and publishers,...
rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
Collision points marker publisher.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.