Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
collision_monitor_node.hpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
16 #define NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
17 
18 #include <string>
19 #include <vector>
20 #include <memory>
21 #include <unordered_map>
22 
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"
27 
28 #include "tf2/time.h"
29 #include "tf2_ros/buffer.h"
30 #include "tf2_ros/transform_listener.h"
31 
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"
36 #include "nav2_msgs/srv/toggle.hpp"
37 
38 #include "nav2_collision_monitor/types.hpp"
39 #include "nav2_collision_monitor/polygon.hpp"
40 #include "nav2_collision_monitor/circle.hpp"
41 #include "nav2_collision_monitor/velocity_polygon.hpp"
42 #include "nav2_collision_monitor/source.hpp"
43 #include "nav2_collision_monitor/scan.hpp"
44 #include "nav2_collision_monitor/pointcloud.hpp"
45 #include "nav2_collision_monitor/range.hpp"
46 #include "nav2_collision_monitor/polygon_source.hpp"
47 
48 namespace nav2_collision_monitor
49 {
50 
55 {
56 public:
61  explicit CollisionMonitor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
66 
67 protected:
74  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
80  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
86  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
92  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
98  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
99 
100 protected:
105  void cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg);
106  void cmdVelInCallbackUnstamped(geometry_msgs::msg::Twist::SharedPtr msg);
113  void publishVelocity(const Action & robot_action, const std_msgs::msg::Header & header);
114 
123  bool getParameters(
124  std::string & cmd_vel_in_topic,
125  std::string & cmd_vel_out_topic,
126  std::string & state_topic);
133  bool configurePolygons(
134  const std::string & base_frame_id,
135  const tf2::Duration & transform_tolerance);
147  bool configureSources(
148  const std::string & base_frame_id,
149  const std::string & odom_frame_id,
150  const tf2::Duration & transform_tolerance,
151  const rclcpp::Duration & source_timeout,
152  const bool base_shift_correction);
153 
159  void process(const Velocity & cmd_vel_in, const std_msgs::msg::Header & header);
160 
171  const std::shared_ptr<Polygon> polygon,
172  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
173  const Velocity & velocity,
174  Action & robot_action) const;
175 
185  bool processApproach(
186  const std::shared_ptr<Polygon> polygon,
187  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
188  const Velocity & velocity,
189  Action & robot_action) const;
190 
196  void notifyActionState(
197  const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const;
198 
202  void publishPolygons() const;
203 
210  const std::shared_ptr<rmw_request_id_t> request_header,
211  const std::shared_ptr<nav2_msgs::srv::Toggle::Request> request,
212  std::shared_ptr<nav2_msgs::srv::Toggle::Response> response);
213 
214  // ----- Variables -----
215 
217  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
219  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
220 
222  std::vector<std::shared_ptr<Polygon>> polygons_;
223 
225  std::vector<std::shared_ptr<Source>> sources_;
226 
227  // Input/output speed controls
229  std::unique_ptr<nav2_util::TwistSubscriber> cmd_vel_in_sub_;
231  std::unique_ptr<nav2_util::TwistPublisher> cmd_vel_out_pub_;
232 
234  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CollisionMonitorState>::SharedPtr
236 
238  rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
240 
242  rclcpp::Service<nav2_msgs::srv::Toggle>::SharedPtr toggle_cm_service_;
243 
245  bool enabled_;
246 
249 
253  rclcpp::Time stop_stamp_;
255  rclcpp::Duration stop_pub_timeout_;
256 }; // class CollisionMonitor
257 
258 } // namespace nav2_collision_monitor
259 
260 #endif // NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
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
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.
rclcpp::Service< nav2_msgs::srv::Toggle >::SharedPtr toggle_cm_service_
Enable/disable collision monitor service.
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.
void toggleCMServiceCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::Toggle::Request > request, std::shared_ptr< nav2_msgs::srv::Toggle::Response > response)
Enable/disable collision monitor service callback.
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 enabled_
Whether collision monitor is enabled.
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.
Action for robot.
Definition: types.hpp:76
Velocity for 2D model of motion.
Definition: types.hpp:25