15 #include "nav2_collision_monitor/polygon.hpp"
20 #include "geometry_msgs/msg/point.hpp"
21 #include "geometry_msgs/msg/point32.hpp"
22 #include "tf2/transform_datatypes.h"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_util/robot_utils.hpp"
26 #include "nav2_util/array_parser.hpp"
28 #include "nav2_collision_monitor/kinematics.hpp"
30 namespace nav2_collision_monitor
34 const nav2_util::LifecycleNode::WeakPtr & node,
35 const std::string & polygon_name,
36 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
37 const std::string & base_frame_id,
38 const tf2::Duration & transform_tolerance)
39 : node_(node), polygon_name_(polygon_name), action_type_(DO_NOTHING),
40 slowdown_ratio_(0.0), linear_limit_(0.0), angular_limit_(0.0),
41 footprint_sub_(nullptr), tf_buffer_(tf_buffer),
42 base_frame_id_(base_frame_id), transform_tolerance_(transform_tolerance)
58 auto node =
node_.lock();
60 throw std::runtime_error{
"Failed to lock node"};
63 std::string polygon_sub_topic, polygon_pub_topic, footprint_topic;
65 if (!
getParameters(polygon_sub_topic, polygon_pub_topic, footprint_topic)) {
71 if (!footprint_topic.empty()) {
74 "[%s]: Making footprint subscriber on %s topic",
76 footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
84 std::vector<Point> poly;
86 for (
const Point & p : poly) {
87 geometry_msgs::msg::Point32 p_s;
91 polygon_.polygon.points.push_back(p_s);
94 rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS();
95 polygon_pub_ = node->create_publisher<geometry_msgs::msg::PolygonStamped>(
96 polygon_pub_topic, polygon_qos);
183 std::vector<geometry_msgs::msg::Point> footprint_vec;
184 std_msgs::msg::Header footprint_header;
185 footprint_sub_->getFootprintInRobotFrame(footprint_vec, footprint_header);
187 std::size_t new_size = footprint_vec.size();
188 poly_.resize(new_size);
190 polygon_.polygon.points.resize(new_size);
192 geometry_msgs::msg::Point32 p_s;
193 for (std::size_t i = 0; i < new_size; i++) {
194 poly_[i] = {footprint_vec[i].x, footprint_vec[i].y};
195 p_s.x = footprint_vec[i].x;
196 p_s.y = footprint_vec[i].y;
201 std::size_t new_size =
polygon_.polygon.points.size();
204 tf2::Stamped<tf2::Transform> tf_transform;
206 !nav2_util::getTransform(
214 poly_.resize(new_size);
215 for (std::size_t i = 0; i < new_size; i++) {
217 tf2::Vector3 p_v3_s(
polygon_.polygon.points[i].x,
polygon_.polygon.points[i].y, 0.0);
218 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
221 poly_[i] = {p_v3_b.x(), p_v3_b.y()};
229 for (
const Point & point : points) {
238 const std::unordered_map<std::string,
239 std::vector<Point>> & sources_collision_points_map)
const
245 for (
const auto & source_name : polygon_sources_names) {
246 const auto & iter = sources_collision_points_map.find(source_name);
247 if (iter != sources_collision_points_map.end()) {
256 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
260 Pose pose = {0.0, 0.0, 0.0};
264 std::vector<Point> collision_points;
267 for (
const auto & source_name : polygon_sources_names) {
268 const auto & iter = sources_collision_points_map.find(source_name);
269 if (iter != sources_collision_points_map.end()) {
270 collision_points.insert(collision_points.end(), iter->second.begin(), iter->second.end());
275 std::vector<Point> points_transformed = collision_points;
288 points_transformed = collision_points;
289 transformPoints(pose, points_transformed);
307 auto node =
node_.lock();
309 throw std::runtime_error{
"Failed to lock node"};
313 polygon_.header.stamp = node->now();
314 auto msg = std::make_unique<geometry_msgs::msg::PolygonStamped>(
polygon_);
319 std::string & polygon_sub_topic,
320 std::string & polygon_pub_topic,
321 std::string & footprint_topic,
322 bool use_dynamic_sub_topic)
324 auto node =
node_.lock();
326 throw std::runtime_error{
"Failed to lock node"};
332 nav2_util::declare_parameter_if_not_declared(
333 node,
polygon_name_ +
".action_type", rclcpp::PARAMETER_STRING);
334 const std::string at_str =
335 node->get_parameter(
polygon_name_ +
".action_type").as_string();
336 if (at_str ==
"stop") {
338 }
else if (at_str ==
"slowdown") {
340 }
else if (at_str ==
"limit") {
342 }
else if (at_str ==
"approach") {
344 }
else if (at_str ==
"none") {
351 nav2_util::declare_parameter_if_not_declared(
352 node,
polygon_name_ +
".enabled", rclcpp::ParameterValue(
true));
355 nav2_util::declare_parameter_if_not_declared(
356 node,
polygon_name_ +
".min_points", rclcpp::ParameterValue(4));
360 nav2_util::declare_parameter_if_not_declared(
361 node,
polygon_name_ +
".max_points", rclcpp::PARAMETER_INTEGER);
365 "[%s]: \"max_points\" parameter was deprecated. Use \"min_points\" instead to specify "
366 "the minimum number of data readings within a zone to trigger the action",
368 }
catch (
const std::exception &) {
373 nav2_util::declare_parameter_if_not_declared(
374 node,
polygon_name_ +
".slowdown_ratio", rclcpp::ParameterValue(0.5));
379 nav2_util::declare_parameter_if_not_declared(
380 node,
polygon_name_ +
".linear_limit", rclcpp::ParameterValue(0.5));
382 nav2_util::declare_parameter_if_not_declared(
383 node,
polygon_name_ +
".angular_limit", rclcpp::ParameterValue(0.5));
388 nav2_util::declare_parameter_if_not_declared(
389 node,
polygon_name_ +
".time_before_collision", rclcpp::ParameterValue(2.0));
391 node->get_parameter(
polygon_name_ +
".time_before_collision").as_double();
392 nav2_util::declare_parameter_if_not_declared(
393 node,
polygon_name_ +
".simulation_time_step", rclcpp::ParameterValue(0.1));
395 node->get_parameter(
polygon_name_ +
".simulation_time_step").as_double();
398 nav2_util::declare_parameter_if_not_declared(
399 node,
polygon_name_ +
".visualize", rclcpp::ParameterValue(
false));
403 nav2_util::declare_parameter_if_not_declared(
405 polygon_pub_topic = node->get_parameter(
polygon_name_ +
".polygon_pub_topic").as_string();
408 nav2_util::declare_parameter_if_not_declared(
409 node,
polygon_name_ +
".polygon_subscribe_transient_local", rclcpp::ParameterValue(
false));
411 node->get_parameter(
polygon_name_ +
".polygon_subscribe_transient_local").as_bool();
413 if (use_dynamic_sub_topic) {
416 nav2_util::declare_parameter_if_not_declared(
417 node,
polygon_name_ +
".polygon_sub_topic", rclcpp::PARAMETER_STRING);
419 node->get_parameter(
polygon_name_ +
".polygon_sub_topic").as_string();
422 nav2_util::declare_parameter_if_not_declared(
424 rclcpp::ParameterValue(
"local_costmap/published_footprint"));
426 node->get_parameter(
polygon_name_ +
".footprint_topic").as_string();
431 nav2_util::declare_parameter_if_not_declared(
432 node,
"observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
433 const std::vector<std::string> observation_sources =
434 node->get_parameter(
"observation_sources").as_string_array();
435 nav2_util::declare_parameter_if_not_declared(
436 node,
polygon_name_ +
".sources_names", rclcpp::ParameterValue(observation_sources));
441 if (std::find(observation_sources.begin(), observation_sources.end(), source_name) ==
442 observation_sources.end())
446 "Observation source [" << source_name <<
447 "] configured for polygon [" <<
getName() <<
448 "] is not defined as one of the node's observation_source!");
452 }
catch (
const std::exception & ex) {
455 "[%s]: Error while getting common polygon parameters: %s",
464 std::string & polygon_sub_topic,
465 std::string & polygon_pub_topic,
466 std::string & footprint_topic)
468 auto node =
node_.lock();
470 throw std::runtime_error{
"Failed to lock node"};
474 polygon_sub_topic.clear();
475 footprint_topic.clear();
477 bool use_dynamic_sub =
true;
480 nav2_util::declare_parameter_if_not_declared(
482 std::string poly_string =
486 }
catch (
const rclcpp::exceptions::ParameterUninitializedException &) {
489 "[%s]: Polygon points are not defined. Using dynamic subscription instead.",
494 polygon_sub_topic, polygon_pub_topic, footprint_topic, use_dynamic_sub))
496 if (use_dynamic_sub && polygon_sub_topic.empty() && footprint_topic.empty()) {
499 "[%s]: Error while getting polygon parameters:"
500 " static points and sub topic both not defined",
511 auto node =
node_.lock();
513 throw std::runtime_error{
"Failed to lock node"};
516 if (!polygon_sub_topic.empty()) {
519 "[%s]: Subscribing on %s topic for polygon",
521 rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS();
523 polygon_qos.transient_local();
525 polygon_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
526 polygon_sub_topic, polygon_qos,
533 std::size_t new_size = msg->polygon.points.size();
538 "[%s]: Polygon should have at least 3 points",
544 tf2::Stamped<tf2::Transform> tf_transform;
546 !nav2_util::getTransform(
554 poly_.resize(new_size);
555 for (std::size_t i = 0; i < new_size; i++) {
557 tf2::Vector3 p_v3_s(msg->polygon.points[i].x, msg->polygon.points[i].y, 0.0);
558 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
561 poly_[i] = {p_v3_b.x(), p_v3_b.y()};
569 rcl_interfaces::msg::SetParametersResult
571 std::vector<rclcpp::Parameter> parameters)
573 rcl_interfaces::msg::SetParametersResult result;
575 for (
auto parameter : parameters) {
576 const auto & param_type = parameter.get_type();
577 const auto & param_name = parameter.get_name();
579 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
585 result.successful =
true;
593 "[%s]: Polygon shape update has been arrived",
605 const int poly_size =
poly_.size();
611 for (j = 0; j < poly_size; j++) {
615 if ((point.y <=
poly_[i].y) == (point.y >
poly_[j].y)) {
617 const double x_inter =
poly_[i].x +
621 if (x_inter > point.x) {
631 std::string & poly_string,
632 std::vector<Point> & polygon)
635 std::vector<std::vector<float>> vvf = nav2_util::parseVVF(poly_string, error);
639 logger_,
"Error parsing polygon parameter %s: '%s'",
640 poly_string.c_str(), error.c_str());
645 if (vvf.size() <= 3) {
648 "Polygon must have at least three points.");
651 for (
unsigned int i = 0; i < vvf.size(); i++) {
652 if (vvf[i].size() == 2) {
656 polygon.push_back(point);
660 "Points in the polygon specification must be pairs of numbers"
661 "Found a point with %d numbers.",
662 static_cast<int>(vvf[i].size()));
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
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.
double getTimeBeforeCollision() const
Obtains required time before collision for current polygon. Applicable for APPROACH model.
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.
rclcpp::Subscription< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_sub_
Polygon subscription.
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.
bool polygon_subscribe_transient_local_
Wether 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_.
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.
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.
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]......
rclcpp_lifecycle::LifecyclePublisher< geometry_msgs::msg::PolygonStamped >::SharedPtr polygon_pub_
Polygon publisher for visualization purposes.
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.