15 #include "nav2_collision_monitor/velocity_polygon.hpp"
17 #include "nav2_util/node_utils.hpp"
19 namespace nav2_collision_monitor
23 const nav2_util::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 nav2_util::declare_parameter_if_not_declared(
54 node,
polygon_name_ +
".velocity_polygons", rclcpp::PARAMETER_STRING_ARRAY);
55 std::vector<std::string> velocity_polygons =
56 node->get_parameter(
polygon_name_ +
".velocity_polygons").as_string_array();
59 nav2_util::declare_parameter_if_not_declared(
60 node,
polygon_name_ +
".holonomic", rclcpp::ParameterValue(
false));
63 for (std::string velocity_polygon_name : velocity_polygons) {
65 std::vector<Point> poly;
66 nav2_util::declare_parameter_if_not_declared(
67 node,
polygon_name_ +
"." + velocity_polygon_name +
".points", rclcpp::PARAMETER_STRING);
68 std::string poly_string =
69 node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".points").as_string();
77 nav2_util::declare_parameter_if_not_declared(
78 node,
polygon_name_ +
"." + velocity_polygon_name +
".linear_min",
79 rclcpp::PARAMETER_DOUBLE);
80 linear_min = node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".linear_min")
85 nav2_util::declare_parameter_if_not_declared(
86 node,
polygon_name_ +
"." + velocity_polygon_name +
".linear_max",
87 rclcpp::PARAMETER_DOUBLE);
88 linear_max = node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".linear_max")
93 nav2_util::declare_parameter_if_not_declared(
94 node,
polygon_name_ +
"." + velocity_polygon_name +
".theta_min",
95 rclcpp::PARAMETER_DOUBLE);
97 node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".theta_min").as_double();
101 nav2_util::declare_parameter_if_not_declared(
102 node,
polygon_name_ +
"." + velocity_polygon_name +
".theta_max",
103 rclcpp::PARAMETER_DOUBLE);
105 node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".theta_max").as_double();
108 double direction_end_angle = 0.0;
109 double direction_start_angle = 0.0;
111 nav2_util::declare_parameter_if_not_declared(
112 node,
polygon_name_ +
"." + velocity_polygon_name +
".direction_end_angle",
113 rclcpp::ParameterValue(M_PI));
114 direction_end_angle =
115 node->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".direction_end_angle")
118 nav2_util::declare_parameter_if_not_declared(
119 node,
polygon_name_ +
"." + velocity_polygon_name +
".direction_start_angle",
120 rclcpp::ParameterValue(-M_PI));
121 direction_start_angle =
123 ->get_parameter(
polygon_name_ +
"." + velocity_polygon_name +
".direction_start_angle")
128 poly, velocity_polygon_name, linear_min, linear_max, theta_min,
129 theta_max, direction_end_angle, direction_start_angle};
132 }
catch (
const std::exception & ex) {
144 if (
isInRange(cmd_vel_in, sub_polygon)) {
146 poly_ = sub_polygon.poly_;
151 geometry_msgs::msg::Point32 p_s;
155 polygon_.polygon.points.push_back(p_s);
162 RCLCPP_WARN_THROTTLE(
164 "Velocity is not covered by any of the velocity polygons. x: %.3f y: %.3f tw: %.3f ",
165 cmd_vel_in.x, cmd_vel_in.y, cmd_vel_in.tw);
173 (cmd_vel_in.x <= sub_polygon.linear_max_ && cmd_vel_in.x >= sub_polygon.linear_min_ &&
174 cmd_vel_in.tw <= sub_polygon.theta_max_ && cmd_vel_in.tw >= sub_polygon.theta_min_);
178 const double direction = std::atan2(cmd_vel_in.y, cmd_vel_in.x);
179 if (sub_polygon.direction_start_angle_ <= sub_polygon.direction_end_angle_) {
181 (direction >= sub_polygon.direction_start_angle_ &&
182 direction <= sub_polygon.direction_end_angle_);
185 (direction >= sub_polygon.direction_start_angle_ ||
186 direction <= sub_polygon.direction_end_angle_);
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
nav2_util::LifecycleNode::WeakPtr node_
Collision Monitor node.
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.
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
Overriden getParameters function for VelocityPolygon parameters.
VelocityPolygon(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)
VelocityPolygon constructor.
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.
void updatePolygon(const Velocity &cmd_vel_in) override
Overriden updatePolygon function for VelocityPolygon.
bool holonomic_
Flag to indicate if the robot is holonomic.
Custom struc to store the parameters of the sub-polygon.
Velocity for 2D model of motion.