15 #include "nav2_collision_monitor/velocity_polygon.hpp"
17 #include "nav2_ros_common/node_utils.hpp"
19 namespace nav2_collision_monitor
23 const nav2::LifecycleNode::WeakPtr & node,
const std::string & polygon_name,
24 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
const std::string & base_frame_id,
25 const tf2::Duration & transform_tolerance)
26 :
Polygon::
Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance)
37 std::string & polygon_sub_topic,
38 std::string & polygon_pub_topic,
39 std::string & footprint_topic)
41 auto node =
node_.lock();
43 throw std::runtime_error{
"Failed to lock node"};
45 clock_ = node->get_clock();
53 std::vector<std::string> velocity_polygons =
54 node->declare_or_get_parameter<std::vector<std::string>>(
61 for (std::string velocity_polygon_name : velocity_polygons) {
63 std::vector<Point> poly;
64 std::string poly_string =
65 node->declare_or_get_parameter<std::string>(
73 double linear_min = node->declare_or_get_parameter<
double>(
77 double linear_max = node->declare_or_get_parameter<
double>(
81 double theta_min = node->declare_or_get_parameter<
double>(
85 double theta_max = node->declare_or_get_parameter<
double>(
89 double direction_end_angle = 0.0;
90 double direction_start_angle = 0.0;
92 direction_end_angle = node->declare_or_get_parameter(
93 polygon_name_ +
"." + velocity_polygon_name +
".direction_end_angle", M_PI);
95 direction_start_angle = node->declare_or_get_parameter(
96 polygon_name_ +
"." + velocity_polygon_name +
".direction_start_angle", -M_PI);
100 poly, velocity_polygon_name, linear_min, linear_max, theta_min,
101 theta_max, direction_end_angle, direction_start_angle};
104 }
catch (
const std::exception & ex) {
116 if (
isInRange(cmd_vel_in, sub_polygon)) {
118 poly_ = sub_polygon.poly_;
123 geometry_msgs::msg::Point32 p_s;
127 polygon_.polygon.points.push_back(p_s);
134 RCLCPP_WARN_THROTTLE(
136 "Velocity is not covered by any of the velocity polygons. x: %.3f y: %.3f tw: %.3f ",
137 cmd_vel_in.x, cmd_vel_in.y, cmd_vel_in.tw);
145 (cmd_vel_in.x <= sub_polygon.linear_max_ && cmd_vel_in.x >= sub_polygon.linear_min_ &&
146 cmd_vel_in.tw <= sub_polygon.theta_max_ && cmd_vel_in.tw >= sub_polygon.theta_min_);
150 const double direction = std::atan2(cmd_vel_in.y, cmd_vel_in.x);
151 if (sub_polygon.direction_start_angle_ <= sub_polygon.direction_end_angle_) {
153 (direction >= sub_polygon.direction_start_angle_ &&
154 direction <= sub_polygon.direction_end_angle_);
157 (direction >= sub_polygon.direction_start_angle_ ||
158 direction <= sub_polygon.direction_end_angle_);
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
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.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
geometry_msgs::msg::PolygonStamped polygon_
Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message.
std::vector< Point > poly_
Polygon points (vertices) in a base_frame_id_.
std::string polygon_name_
Name of polygon.
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
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]......
std::vector< SubPolygonParameter > sub_polygons_
Vector to store the parameters of the sub-polygon.
bool getParameters(std::string &, std::string &polygon_pub_topic, std::string &) override
Overridden getParameters function for VelocityPolygon parameters.
bool isInRange(const Velocity &cmd_vel_in, const SubPolygonParameter &sub_polygon_param)
Check if the velocities and direction is in expected range.
virtual ~VelocityPolygon()
VelocityPolygon destructor.
VelocityPolygon(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)
VelocityPolygon constructor.
void updatePolygon(const Velocity &cmd_vel_in) override
Overridden updatePolygon function for VelocityPolygon.
bool holonomic_
Flag to indicate if the robot is holonomic.
Custom struct to store the parameters of the sub-polygon.
Velocity for 2D model of motion.