Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
collision_detector_node.hpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
2 // Copyright (c) 2023 Pixel Robotics GmbH
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_COLLISION_MONITOR__COLLISION_DETECTOR_NODE_HPP_
17 #define NAV2_COLLISION_MONITOR__COLLISION_DETECTOR_NODE_HPP_
18 
19 #include <string>
20 #include <vector>
21 #include <memory>
22 
23 #include "rclcpp/rclcpp.hpp"
24 
25 #include "tf2/time.hpp"
26 #include "tf2_ros/buffer.hpp"
27 #include "tf2_ros/transform_listener.hpp"
28 
29 #include "nav2_ros_common/lifecycle_node.hpp"
30 #include "nav2_msgs/msg/collision_detector_state.hpp"
31 #include "visualization_msgs/msg/marker_array.hpp"
32 
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"
42 
43 namespace nav2_collision_monitor
44 {
45 
50 {
51 public:
56  explicit CollisionDetector(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
61 
62 protected:
69  nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
75  nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
81  nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
87  nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
93  nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
94 
95 protected:
100  bool getParameters();
107  bool configurePolygons(
108  const std::string & base_frame_id,
109  const tf2::Duration & transform_tolerance);
121  bool configureSources(
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);
127 
131  void process();
132 
136  void publishPolygons() const;
137 
138  // ----- Variables -----
139 
141  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
143  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
144 
146  std::vector<std::shared_ptr<Polygon>> polygons_;
148  std::vector<std::shared_ptr<Source>> sources_;
149 
151  nav2::Publisher<nav2_msgs::msg::CollisionDetectorState>::SharedPtr
154  nav2::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr
157  rclcpp::TimerBase::SharedPtr timer_;
158 
160  double frequency_;
161 }; // class CollisionDetector
162 
163 } // namespace nav2_collision_monitor
164 
165 #endif // NAV2_COLLISION_MONITOR__COLLISION_DETECTOR_NODE_HPP_
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates LifecyclePublishers, polygons and main processor, creates bond connection
nav2::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
Collision points marker publisher.
bool getParameters()
Supporting routine obtaining all ROS-parameters.
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.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
nav2::Publisher< nav2_msgs::msg::CollisionDetectorState >::SharedPtr state_pub_
collision monitor state publisher
~CollisionDetector()
Destructor for the nav2_collision_monitor::CollisionDetector.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all subscribers/publishers, polygons/data sources arrays
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
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes and obtains ROS-parameters, creates main subscribers and publishers,...
std::vector< std::shared_ptr< Polygon > > polygons_
Polygons array.
CollisionDetector(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_collision_monitor::CollisionDetector.