Nav2 Navigation Stack - jazzy  jazzy
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 #include <unordered_map>
22 
23 #include "rclcpp/rclcpp.hpp"
24 #include "geometry_msgs/msg/polygon_stamped.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 getMinPoints() const;
104  double getSlowdownRatio() const;
110  double getLinearLimit() const;
116  double getAngularLimit() const;
122  double getTimeBeforeCollision() const;
123 
128  virtual void getPolygon(std::vector<Point> & poly) const;
129 
134  std::vector<std::string> getSourcesNames() const;
135 
140  virtual bool isShapeSet();
141 
145  virtual void updatePolygon(const Velocity & /*cmd_vel_in*/);
146 
153  virtual int getPointsInside(const std::vector<Point> & points) const;
154 
163  virtual int getPointsInside(
164  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map) const;
165 
175  double getCollisionTime(
176  const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
177  const Velocity & velocity) const;
178 
182  void publish();
183 
184 protected:
196  bool getCommonParameters(
197  std::string & polygon_sub_topic,
198  std::string & polygon_pub_topic,
199  std::string & footprint_topic,
200  bool use_dynamic_sub = false);
201 
211  virtual bool getParameters(
212  std::string & polygon_sub_topic,
213  std::string & polygon_pub_topic,
214  std::string & footprint_topic);
215 
221  virtual void createSubscription(std::string & polygon_sub_topic);
222 
227  void updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
228 
233  void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
234 
239  rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
240  std::vector<rclcpp::Parameter> parameters);
241 
247  bool isPointInside(const Point & point) const;
248 
255  bool getPolygonFromString(std::string & poly_string, std::vector<Point> & polygon);
256 
257  // ----- Variables -----
258 
260  nav2_util::LifecycleNode::WeakPtr node_;
262  rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")};
264  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
265 
266  // Basic parameters
268  std::string polygon_name_;
270  ActionType action_type_;
284  bool enabled_;
288  rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_sub_;
290  std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
292  std::vector<std::string> sources_names_;
293 
294  // Global variables
296  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
298  std::string base_frame_id_;
300  tf2::Duration transform_tolerance_;
301 
302  // Visualization
306  geometry_msgs::msg::PolygonStamped polygon_;
308  rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
309 
311  std::vector<Point> poly_;
312 }; // class Polygon
313 
314 } // namespace nav2_collision_monitor
315 
316 #endif // NAV2_COLLISION_MONITOR__POLYGON_HPP_
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Definition: polygon.hpp:43
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
Definition: polygon.hpp:260
virtual bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic)
Supporting routine obtaining polygon-specific ROS-parameters.
Definition: polygon.cpp:463
int getMinPoints() const
Obtains polygon minimum points to enter inside polygon causing the action.
Definition: polygon.cpp:135
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
Definition: polygon.cpp:155
virtual void updatePolygon(const Velocity &)
Updates polygon from footprint subscriber (if any)
Definition: polygon.cpp:179
virtual int getPointsInside(const std::vector< Point > &points) const
Gets number of points inside given polygon.
Definition: polygon.cpp:226
bool getCommonParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic, bool use_dynamic_sub=false)
Supporting routine obtaining ROS-parameters common for all shapes.
Definition: polygon.cpp:318
double time_before_collision_
Time before collision in seconds.
Definition: polygon.hpp:280
bool enabled_
Whether polygon is enabled.
Definition: polygon.hpp:284
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
Definition: polygon.hpp:262
ActionType action_type_
Action type for the polygon.
Definition: polygon.hpp:270
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
Definition: polygon.hpp:306
rclcpp::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_sub_
Polygon subscription.
Definition: polygon.hpp:288
virtual void createSubscription(std::string &polygon_sub_topic)
Creates polygon or radius topic subscription.
Definition: polygon.cpp:509
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
Definition: polygon.hpp:264
bool polygon_subscribe_transient_local_
Wether the subscription to polygon topic has transient local QoS durability.
Definition: polygon.hpp:286
virtual bool isShapeSet()
Returns true if polygon points were set. Otherwise, prints a warning and returns false.
Definition: polygon.cpp:170
double simulation_time_step_
Time step for robot movement simulation.
Definition: polygon.hpp:282
void activate()
Activates polygon lifecycle publisher.
Definition: polygon.cpp:106
bool configure()
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifec...
Definition: polygon.cpp:56
bool isPointInside(const Point &point) const
Checks if point is inside polygon.
Definition: polygon.cpp:598
double getLinearLimit() const
Obtains speed linear limit for current polygon. Applicable for LIMIT model.
Definition: polygon.cpp:145
std::string getName() const
Returns the name of polygon.
Definition: polygon.cpp:120
virtual void getPolygon(std::vector< Point > &poly) const
Gets polygon points.
Definition: polygon.cpp:165
tf2::Duration transform_tolerance_
Transform tolerance.
Definition: polygon.hpp:300
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
Definition: polygon.hpp:296
ActionType getActionType() const
Obtains polygon action type.
Definition: polygon.cpp:125
int min_points_
Minimum number of data readings within a zone to trigger the action.
Definition: polygon.hpp:272
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
Definition: polygon.hpp:311
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:33
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Definition: polygon.cpp:570
std::vector< std::string > sources_names_
Name of the observation sources to check for polygon.
Definition: polygon.hpp:292
void deactivate()
Deactivates polygon lifecycle publisher.
Definition: polygon.cpp:113
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub_
Footprint subscriber.
Definition: polygon.hpp:290
void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg)
Dynamic polygon callback.
Definition: polygon.cpp:589
double getSlowdownRatio() const
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
Definition: polygon.cpp:140
double getAngularLimit() const
Obtains speed angular z limit for current polygon. Applicable for LIMIT model.
Definition: polygon.cpp:150
double getCollisionTime(const std::unordered_map< std::string, std::vector< Point >> &sources_collision_points_map, const Velocity &velocity) const
Obtains estimated (simulated) time before a collision. Applicable for APPROACH model.
Definition: polygon.cpp:255
std::string polygon_name_
Name of polygon.
Definition: polygon.hpp:268
double linear_limit_
Robot linear limit.
Definition: polygon.hpp:276
virtual ~Polygon()
Polygon destructor.
Definition: polygon.cpp:47
bool getEnabled() const
Obtains polygon enabled state.
Definition: polygon.cpp:130
double angular_limit_
Robot angular limit.
Definition: polygon.hpp:278
bool getPolygonFromString(std::string &poly_string, std::vector< Point > &polygon)
Extracts Polygon points from a string with of the form [[x1,y1],[x2,y2],[x3,y3]......
Definition: polygon.cpp:630
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
Definition: polygon.hpp:308
bool visualize_
Whether to publish the polygon.
Definition: polygon.hpp:304
std::vector< std::string > getSourcesNames() const
Obtains the name of the observation sources for current polygon.
Definition: polygon.cpp:160
std::string base_frame_id_
Base frame ID.
Definition: polygon.hpp:298
double slowdown_ratio_
Robot slowdown (share of its actual speed)
Definition: polygon.hpp:274
void publish()
Publishes polygon message into a its own topic.
Definition: polygon.cpp:301
Velocity for 2D model of motion.
Definition: types.hpp:25