Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
polygon.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__POLYGON_HPP_
16 #define NAV2_COLLISION_MONITOR__POLYGON_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "geometry_msgs/msg/polygon_stamped.hpp"
24 #include "geometry_msgs/msg/polygon.hpp"
25 
26 #include "tf2/time.h"
27 #include "tf2_ros/buffer.h"
28 
29 #include "nav2_util/lifecycle_node.hpp"
30 #include "nav2_costmap_2d/footprint_subscriber.hpp"
31 
32 #include "nav2_collision_monitor/types.hpp"
33 
34 namespace nav2_collision_monitor
35 {
36 
42 class Polygon
43 {
44 public:
53  Polygon(
54  const nav2_util::LifecycleNode::WeakPtr & node,
55  const std::string & polygon_name,
56  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
57  const std::string & base_frame_id,
58  const tf2::Duration & transform_tolerance);
62  virtual ~Polygon();
63 
69  bool configure();
73  void activate();
77  void deactivate();
78 
83  std::string getName() const;
88  ActionType getActionType() const;
93  bool getEnabled() const;
98  int getMaxPoints() const;
104  double getSlowdownRatio() const;
110  double getTimeBeforeCollision() const;
111 
116  virtual void getPolygon(std::vector<Point> & poly) const;
117 
121  void updatePolygon();
122 
129  virtual int getPointsInside(const std::vector<Point> & points) const;
130 
139  double getCollisionTime(
140  const std::vector<Point> & collision_points,
141  const Velocity & velocity) const;
142 
146  void publish() const;
147 
148 protected:
154  bool getCommonParameters(std::string & polygon_pub_topic);
155 
162  virtual bool getParameters(std::string & polygon_pub_topic, std::string & footprint_topic);
163 
174  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
175  std::vector<rclcpp::Parameter> parameters);
176 
177  bool isPointInside(const Point & point) const;
178 
179  // ----- Variables -----
180 
182  nav2_util::LifecycleNode::WeakPtr node_;
184  rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")};
186  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
187 
188  // Basic parameters
190  std::string polygon_name_;
192  ActionType action_type_;
202  std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
204  bool enabled_;
205 
206  // Global variables
208  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
210  std::string base_frame_id_;
212  tf2::Duration transform_tolerance_;
213 
214  // Visualization
218  geometry_msgs::msg::Polygon polygon_;
220  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
221 
223  std::vector<Point> poly_;
224 }; // class Polygon
225 
226 } // namespace nav2_collision_monitor
227 
228 #endif // NAV2_COLLISION_MONITOR__POLYGON_HPP_
Basic polygon shape class. For STOP/SLOWDOWN model it represents zone around the robot while for APPR...
Definition: polygon.hpp:43
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:182
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
Definition: polygon.cpp:132
int max_points_
Maximum number of data readings within a zone to not trigger the action.
Definition: polygon.hpp:194
bool getCommonParameters(std::string &polygon_pub_topic)
Supporting routine obtaining ROS-parameters common for all shapes.
Definition: polygon.cpp:232
virtual int getPointsInside(const std::vector< Point > &points) const
Gets number of points inside given polygon.
Definition: polygon.cpp:164
double time_before_collision_
Time before collision in seconds.
Definition: polygon.hpp:198
bool enabled_
Whether polygon is enabled.
Definition: polygon.hpp:204
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: polygon.hpp:184
ActionType action_type_
Action type for the polygon.
Definition: polygon.hpp:192
double getCollisionTime(const std::vector< Point > &collision_points, const Velocity &velocity) const
Obtains estimated (simulated) time before a collision. Applicable for APPROACH model.
Definition: polygon.cpp:175
int getMaxPoints() const
Obtains polygon maximum points to enter inside polygon causing no action.
Definition: polygon.cpp:122
void publish() const
Publishes polygon message into a its own topic.
Definition: polygon.cpp:210
void updatePolygon()
Updates polygon from footprint subscriber (if any)
Definition: polygon.cpp:142
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: polygon.hpp:186
double simulation_time_step_
Time step for robot movement simulation.
Definition: polygon.hpp:200
void activate()
Activates polygon lifecycle publisher.
Definition: polygon.cpp:93
bool configure()
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifec...
Definition: polygon.cpp:50
geometry_msgs::msg::Polygon polygon_
Polygon points stored for later publishing.
Definition: polygon.hpp:218
std::string getName() const
Returns the name of polygon.
Definition: polygon.cpp:107
virtual void getPolygon(std::vector< Point > &poly) const
Gets polygon points.
Definition: polygon.cpp:137
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: polygon.hpp:212
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: polygon.hpp:208
ActionType getActionType() const
Obtains polygon action type.
Definition: polygon.cpp:112
std::vector< Point > poly_
Polygon points (vertices)
Definition: polygon.hpp:223
Polygon(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &polygon_name, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
Polygon constructor.
Definition: polygon.cpp:30
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Checks if point is inside polygon.
Definition: polygon.cpp:368
void deactivate()
Deactivates polygon lifecycle publisher.
Definition: polygon.cpp:100
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub_
Footprint subscriber.
Definition: polygon.hpp:202
double getSlowdownRatio() const
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
Definition: polygon.cpp:127
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:190
virtual ~Polygon()
Polygon destructor.
Definition: polygon.cpp:43
bool getEnabled() const
Obtains polygon enabled state.
Definition: polygon.cpp:117
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
Definition: polygon.hpp:220
bool visualize_
Whether to publish the polygon.
Definition: polygon.hpp:216
std::string base_frame_id_
Base frame ID.
Definition: polygon.hpp:210
virtual bool getParameters(std::string &polygon_pub_topic, std::string &footprint_topic)
Supporting routine obtaining polygon-specific ROS-parameters.
Definition: polygon.cpp:302
double slowdown_ratio_
Robot slowdown (share of its actual speed)
Definition: polygon.hpp:196
Velocity for 2D model of motion.
Definition: types.hpp:23