Nav2 Navigation Stack - humble  humble
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 
22 #include "rclcpp/rclcpp.hpp"
23 #include "geometry_msgs/msg/twist.hpp"
24 
25 #include "tf2/time.h"
26 #include "tf2_ros/buffer.h"
27 #include "tf2_ros/transform_listener.h"
28 
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "nav2_util/robot_utils.hpp"
31 
32 #include "nav2_collision_monitor/types.hpp"
33 #include "nav2_collision_monitor/polygon.hpp"
34 #include "nav2_collision_monitor/circle.hpp"
35 #include "nav2_collision_monitor/source.hpp"
36 #include "nav2_collision_monitor/scan.hpp"
37 #include "nav2_collision_monitor/pointcloud.hpp"
38 #include "nav2_collision_monitor/range.hpp"
39 
40 namespace nav2_collision_monitor
41 {
42 
47 {
48 public:
53  explicit CollisionMonitor(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
58 
59 protected:
66  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
72  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
78  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
84  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
90  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
91 
92 protected:
97  void cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg);
103  void publishVelocity(const Action & robot_action);
104 
112  bool getParameters(
113  std::string & cmd_vel_in_topic,
114  std::string & cmd_vel_out_topic);
121  bool configurePolygons(
122  const std::string & base_frame_id,
123  const tf2::Duration & transform_tolerance);
135  bool configureSources(
136  const std::string & base_frame_id,
137  const std::string & odom_frame_id,
138  const tf2::Duration & transform_tolerance,
139  const rclcpp::Duration & source_timeout,
140  const bool base_shift_correction);
141 
146  void process(const Velocity & cmd_vel_in);
147 
156  bool processStopSlowdown(
157  const std::shared_ptr<Polygon> polygon,
158  const std::vector<Point> & collision_points,
159  const Velocity & velocity,
160  Action & robot_action) const;
161 
170  bool processApproach(
171  const std::shared_ptr<Polygon> polygon,
172  const std::vector<Point> & collision_points,
173  const Velocity & velocity,
174  Action & robot_action) const;
175 
181  void printAction(
182  const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const;
183 
187  void publishPolygons() const;
188 
189  // ----- Variables -----
190 
192  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
194  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
195 
197  std::vector<std::shared_ptr<Polygon>> polygons_;
198 
200  std::vector<std::shared_ptr<Source>> sources_;
201 
202  // Input/output speed controls
204  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_in_sub_;
206  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_out_pub_;
207 
210 
214  rclcpp::Time stop_stamp_;
216  rclcpp::Duration stop_pub_timeout_;
217 }; // class CollisionMonitor
218 
219 } // namespace nav2_collision_monitor
220 
221 #endif // NAV2_COLLISION_MONITOR__COLLISION_MONITOR_NODE_HPP_
void cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
Callback for input cmd_vel.
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::Twist >::SharedPtr 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
void publishVelocity(const Action &robot_action)
Publishes output cmd_vel. If robot was stopped more than stop_pub_timeout_ seconds,...
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_safery::CollisionMonitor.
rclcpp::Time stop_stamp_
Latest timestamp when robot has 0-velocity.
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr cmd_vel_in_sub_
@beirf Input cmd_vel subscriber
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
bool processStopSlowdown(const std::shared_ptr< Polygon > polygon, const std::vector< Point > &collision_points, const Velocity &velocity, Action &robot_action) const
Processes the polygon of STOP and SLOWDOWN action type.
void printAction(const Action &robot_action, const std::shared_ptr< Polygon > action_polygon) const
Prints robot action and polygon caused it (if it was)
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 processApproach(const std::shared_ptr< Polygon > polygon, const std::vector< Point > &collision_points, const Velocity &velocity, Action &robot_action) const
Processes APPROACH action type.
void process(const Velocity &cmd_vel_in)
Main processing routine.
CollisionMonitor(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_safery::CollisionMonitor.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
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.
bool getParameters(std::string &cmd_vel_in_topic, std::string &cmd_vel_out_topic)
Supporting routine obtaining all ROS-parameters.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
Action for robot.
Definition: types.hpp:73
Velocity for 2D model of motion.
Definition: types.hpp:23