15 #ifndef NAV2_COLLISION_MONITOR__POLYGON_HPP_
16 #define NAV2_COLLISION_MONITOR__POLYGON_HPP_
21 #include <unordered_map>
23 #include "rclcpp/rclcpp.hpp"
24 #include "geometry_msgs/msg/polygon_stamped.hpp"
26 #include "tf2/time.hpp"
27 #include "tf2_ros/buffer.hpp"
29 #include "nav2_ros_common/lifecycle_node.hpp"
30 #include "nav2_costmap_2d/footprint_subscriber.hpp"
32 #include "nav2_collision_monitor/types.hpp"
34 namespace nav2_collision_monitor
54 const nav2::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);
128 virtual void getPolygon(std::vector<Point> & poly)
const;
164 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map)
const;
176 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
197 std::string & polygon_sub_topic,
198 std::string & polygon_pub_topic,
199 std::string & footprint_topic,
200 bool use_dynamic_sub =
false);
212 std::string & polygon_sub_topic,
213 std::string & polygon_pub_topic,
214 std::string & footprint_topic);
227 void updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
233 void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
240 std::vector<rclcpp::Parameter> parameters);
262 rclcpp::Logger
logger_{rclcpp::get_logger(
"collision_monitor")};
288 nav2::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr
polygon_sub_;
310 nav2::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr
polygon_pub_;
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
virtual bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic)
Supporting routine obtaining polygon-specific ROS-parameters.
int getMinPoints() const
Obtains polygon minimum points to enter inside polygon causing the action.
nav2::Publisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
Polygon(const nav2::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.
rclcpp::Clock::SharedPtr node_clock_
Collision monitor node's clock.
virtual void updatePolygon(const Velocity &)
Updates polygon from footprint subscriber (if any)
virtual int getPointsInside(const std::vector< Point > &points) const
Gets number of points inside given polygon.
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.
double time_before_collision_
Time before collision in seconds.
bool enabled_
Whether polygon is enabled.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
ActionType action_type_
Action type for the polygon.
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
virtual void createSubscription(std::string &polygon_sub_topic)
Creates polygon or radius topic subscription.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
nav2::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_sub_
Polygon subscription.
bool polygon_subscribe_transient_local_
Whether the subscription to polygon topic has transient local QoS durability.
virtual bool isShapeSet()
Returns true if polygon points were set. Otherwise, prints a warning and returns false.
double simulation_time_step_
Time step for robot movement simulation.
void activate()
Activates polygon lifecycle publisher.
bool configure()
Shape configuration routine. Obtains ROS-parameters related to shape object and creates polygon lifec...
bool isPointInside(const Point &point) const
Checks if point is inside polygon.
double getLinearLimit() const
Obtains speed linear limit for current polygon. Applicable for LIMIT model.
std::string getName() const
Returns the name of polygon.
virtual void getPolygon(std::vector< Point > &poly) const
Gets polygon points.
tf2::Duration transform_tolerance_
Transform tolerance.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
ActionType getActionType() const
Obtains polygon action type.
int min_points_
Minimum number of data readings within a zone to trigger the action.
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
std::vector< std::string > sources_names_
Name of the observation sources to check for polygon.
void deactivate()
Deactivates polygon lifecycle publisher.
std::unique_ptr< nav2_costmap_2d::FootprintSubscriber > footprint_sub_
Footprint subscriber.
void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg)
Dynamic polygon callback.
double getSlowdownRatio() const
Obtains speed slowdown ratio for current polygon. Applicable for SLOWDOWN model.
double getAngularLimit() const
Obtains speed angular z limit for current polygon. Applicable for LIMIT model.
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.
std::string polygon_name_
Name of polygon.
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
double linear_limit_
Robot linear limit.
virtual ~Polygon()
Polygon destructor.
bool getEnabled() const
Obtains polygon enabled state.
double angular_limit_
Robot angular limit.
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]......
bool visualize_
Whether to publish the polygon.
std::vector< std::string > getSourcesNames() const
Obtains the name of the observation sources for current polygon.
std::string base_frame_id_
Base frame ID.
double slowdown_ratio_
Robot slowdown (share of its actual speed)
void publish()
Publishes polygon message into a its own topic.
Velocity for 2D model of motion.