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.hpp"
24 #include "nav2_ros_common/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::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),
60 auto node =
node_.lock();
62 throw std::runtime_error{
"Failed to lock node"};
66 std::string polygon_sub_topic, polygon_pub_topic, footprint_topic;
68 if (!
getParameters(polygon_sub_topic, polygon_pub_topic, footprint_topic)) {
74 if (!footprint_topic.empty()) {
77 "[%s]: Making footprint subscriber on %s topic",
79 footprint_sub_ = std::make_unique<nav2_costmap_2d::FootprintSubscriber>(
87 std::vector<Point> poly;
89 for (
const Point & p : poly) {
90 geometry_msgs::msg::Point32 p_s;
94 polygon_.polygon.points.push_back(p_s);
97 polygon_pub_ = node->create_publisher<geometry_msgs::msg::PolygonStamped>(
185 std::vector<geometry_msgs::msg::Point> footprint_vec;
186 std_msgs::msg::Header footprint_header;
187 footprint_sub_->getFootprintInRobotFrame(footprint_vec, footprint_header);
189 std::size_t new_size = footprint_vec.size();
190 poly_.resize(new_size);
192 polygon_.polygon.points.resize(new_size);
194 geometry_msgs::msg::Point32 p_s;
195 for (std::size_t i = 0; i < new_size; i++) {
196 poly_[i] = {footprint_vec[i].x, footprint_vec[i].y};
197 p_s.x = footprint_vec[i].x;
198 p_s.y = footprint_vec[i].y;
203 std::size_t new_size =
polygon_.polygon.points.size();
206 tf2::Stamped<tf2::Transform> tf_transform;
208 !nav2_util::getTransform(
216 poly_.resize(new_size);
217 for (std::size_t i = 0; i < new_size; i++) {
219 tf2::Vector3 p_v3_s(
polygon_.polygon.points[i].x,
polygon_.polygon.points[i].y, 0.0);
220 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
223 poly_[i] = {p_v3_b.x(), p_v3_b.y()};
231 for (
const Point & point : points) {
240 const std::unordered_map<std::string,
241 std::vector<Point>> & sources_collision_points_map)
const
247 for (
const auto & source_name : polygon_sources_names) {
248 const auto & iter = sources_collision_points_map.find(source_name);
249 if (iter != sources_collision_points_map.end()) {
258 const std::unordered_map<std::string, std::vector<Point>> & sources_collision_points_map,
262 Pose pose = {0.0, 0.0, 0.0};
266 std::vector<Point> collision_points;
269 for (
const auto & source_name : polygon_sources_names) {
270 const auto & iter = sources_collision_points_map.find(source_name);
271 if (iter != sources_collision_points_map.end()) {
272 collision_points.insert(collision_points.end(), iter->second.begin(), iter->second.end());
277 std::vector<Point> points_transformed = collision_points;
290 points_transformed = collision_points;
291 transformPoints(pose, points_transformed);
309 auto node =
node_.lock();
311 throw std::runtime_error{
"Failed to lock node"};
315 polygon_.header.stamp = node->now();
316 auto msg = std::make_unique<geometry_msgs::msg::PolygonStamped>(
polygon_);
321 std::string & polygon_sub_topic,
322 std::string & polygon_pub_topic,
323 std::string & footprint_topic,
324 bool use_dynamic_sub_topic)
326 auto node =
node_.lock();
328 throw std::runtime_error{
"Failed to lock node"};
334 nav2::declare_parameter_if_not_declared(
335 node,
polygon_name_ +
".action_type", rclcpp::PARAMETER_STRING);
336 const std::string at_str =
337 node->get_parameter(
polygon_name_ +
".action_type").as_string();
338 if (at_str ==
"stop") {
340 }
else if (at_str ==
"slowdown") {
342 }
else if (at_str ==
"limit") {
344 }
else if (at_str ==
"approach") {
346 }
else if (at_str ==
"none") {
353 nav2::declare_parameter_if_not_declared(
354 node,
polygon_name_ +
".enabled", rclcpp::ParameterValue(
true));
357 nav2::declare_parameter_if_not_declared(
358 node,
polygon_name_ +
".min_points", rclcpp::ParameterValue(4));
362 nav2::declare_parameter_if_not_declared(
363 node,
polygon_name_ +
".max_points", rclcpp::PARAMETER_INTEGER);
367 "[%s]: \"max_points\" parameter was deprecated. Use \"min_points\" instead to specify "
368 "the minimum number of data readings within a zone to trigger the action",
370 }
catch (
const std::exception &) {
375 nav2::declare_parameter_if_not_declared(
376 node,
polygon_name_ +
".slowdown_ratio", rclcpp::ParameterValue(0.5));
381 nav2::declare_parameter_if_not_declared(
382 node,
polygon_name_ +
".linear_limit", rclcpp::ParameterValue(0.5));
384 nav2::declare_parameter_if_not_declared(
385 node,
polygon_name_ +
".angular_limit", rclcpp::ParameterValue(0.5));
390 nav2::declare_parameter_if_not_declared(
391 node,
polygon_name_ +
".time_before_collision", rclcpp::ParameterValue(2.0));
393 node->get_parameter(
polygon_name_ +
".time_before_collision").as_double();
394 nav2::declare_parameter_if_not_declared(
395 node,
polygon_name_ +
".simulation_time_step", rclcpp::ParameterValue(0.1));
397 node->get_parameter(
polygon_name_ +
".simulation_time_step").as_double();
400 nav2::declare_parameter_if_not_declared(
401 node,
polygon_name_ +
".visualize", rclcpp::ParameterValue(
false));
405 nav2::declare_parameter_if_not_declared(
407 polygon_pub_topic = node->get_parameter(
polygon_name_ +
".polygon_pub_topic").as_string();
410 nav2::declare_parameter_if_not_declared(
411 node,
polygon_name_ +
".polygon_subscribe_transient_local", rclcpp::ParameterValue(
false));
413 node->get_parameter(
polygon_name_ +
".polygon_subscribe_transient_local").as_bool();
415 if (use_dynamic_sub_topic) {
418 nav2::declare_parameter_if_not_declared(
419 node,
polygon_name_ +
".polygon_sub_topic", rclcpp::PARAMETER_STRING);
421 node->get_parameter(
polygon_name_ +
".polygon_sub_topic").as_string();
424 nav2::declare_parameter_if_not_declared(
426 rclcpp::ParameterValue(
"local_costmap/published_footprint"));
428 node->get_parameter(
polygon_name_ +
".footprint_topic").as_string();
433 nav2::declare_parameter_if_not_declared(
434 node,
"observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
435 const std::vector<std::string> observation_sources =
436 node->get_parameter(
"observation_sources").as_string_array();
437 nav2::declare_parameter_if_not_declared(
438 node,
polygon_name_ +
".sources_names", rclcpp::ParameterValue(observation_sources));
443 if (std::find(observation_sources.begin(), observation_sources.end(), source_name) ==
444 observation_sources.end())
448 "Observation source [" << source_name <<
449 "] configured for polygon [" <<
getName() <<
450 "] is not defined as one of the node's observation_source!");
454 }
catch (
const std::exception & ex) {
457 "[%s]: Error while getting common polygon parameters: %s",
466 std::string & polygon_sub_topic,
467 std::string & polygon_pub_topic,
468 std::string & footprint_topic)
470 auto node =
node_.lock();
472 throw std::runtime_error{
"Failed to lock node"};
476 polygon_sub_topic.clear();
477 footprint_topic.clear();
479 bool use_dynamic_sub =
true;
482 nav2::declare_parameter_if_not_declared(
484 std::string poly_string =
488 }
catch (
const rclcpp::exceptions::ParameterUninitializedException &) {
491 "[%s]: Polygon points are not defined. Using dynamic subscription instead.",
496 polygon_sub_topic, polygon_pub_topic, footprint_topic, use_dynamic_sub))
498 if (use_dynamic_sub && polygon_sub_topic.empty() && footprint_topic.empty()) {
501 "[%s]: Error while getting polygon parameters:"
502 " static points and sub topic both not defined",
513 auto node =
node_.lock();
515 throw std::runtime_error{
"Failed to lock node"};
518 if (!polygon_sub_topic.empty()) {
521 "[%s]: Subscribing on %s topic for polygon",
525 polygon_qos.transient_local();
527 polygon_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
536 std::size_t new_size = msg->polygon.points.size();
541 "[%s]: Polygon should have at least 3 points",
547 tf2::Stamped<tf2::Transform> tf_transform;
549 !nav2_util::getTransform(
557 poly_.resize(new_size);
558 for (std::size_t i = 0; i < new_size; i++) {
560 tf2::Vector3 p_v3_s(msg->polygon.points[i].x, msg->polygon.points[i].y, 0.0);
561 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
564 poly_[i] = {p_v3_b.x(), p_v3_b.y()};
572 rcl_interfaces::msg::SetParametersResult
574 std::vector<rclcpp::Parameter> parameters)
576 rcl_interfaces::msg::SetParametersResult result;
578 for (
auto parameter : parameters) {
579 const auto & param_type = parameter.get_type();
580 const auto & param_name = parameter.get_name();
584 if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
590 result.successful =
true;
596 RCLCPP_INFO_THROTTLE(
600 "[%s]: Polygon shape update has arrived",
612 const int poly_size =
poly_.size();
618 for (j = 0; j < poly_size; j++) {
622 if ((point.y <=
poly_[i].y) == (point.y >
poly_[j].y)) {
624 const double x_inter =
poly_[i].x +
628 if (x_inter > point.x) {
638 std::string & poly_string,
639 std::vector<Point> & polygon)
642 std::vector<std::vector<float>> vvf = nav2_util::parseVVF(poly_string, error);
646 logger_,
"Error parsing polygon parameter %s: '%s'",
647 poly_string.c_str(), error.c_str());
652 if (vvf.size() <= 3) {
655 "Polygon must have at least three points.");
658 for (
unsigned int i = 0; i < vvf.size(); i++) {
659 if (vvf[i].size() == 2) {
663 polygon.push_back(point);
667 "Points in the polygon specification must be pairs of numbers"
668 "Found a point with %d numbers.",
669 static_cast<int>(vvf[i].size()));
A QoS profile for standard reliable topics with a history of 10 messages.
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.