20 #include "nav2_route/plugins/route_operations/collision_monitor.hpp"
26 const nav2::LifecycleNode::SharedPtr node,
27 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_subscriber,
28 const std::string & name)
31 clock_ = node->get_clock();
32 logger_ = node->get_logger();
33 last_check_time_ = clock_->now();
35 std::string server_costmap_topic = node->get_parameter(
"costmap_topic").as_string();
36 nav2::declare_parameter_if_not_declared(
37 node,
getName() +
".costmap_topic", rclcpp::ParameterValue(
"local_costmap/costmap_raw"));
38 std::string costmap_topic = node->get_parameter(
getName() +
".costmap_topic").as_string();
39 if (costmap_topic != server_costmap_topic) {
40 RCLCPP_INFO(node->get_logger(),
41 "Using costmap topic: %s instead of server costmap topic: %s for CollisionMonitor.",
42 costmap_topic.c_str(), server_costmap_topic.c_str());
43 costmap_subscriber_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(node, costmap_topic);
44 topic_ = costmap_topic;
46 costmap_subscriber_ = costmap_subscriber;
47 topic_ = server_costmap_topic;
50 nav2::declare_parameter_if_not_declared(
51 node,
getName() +
".rate", rclcpp::ParameterValue(1.0));
52 double checking_rate = node->get_parameter(
getName() +
".rate").as_double();
53 checking_duration_ = rclcpp::Duration::from_seconds(1.0 / checking_rate);
55 nav2::declare_parameter_if_not_declared(
56 node,
getName() +
".reroute_on_collision", rclcpp::ParameterValue(
true));
57 reroute_on_collision_ = node->get_parameter(
getName() +
".reroute_on_collision").as_bool();
59 nav2::declare_parameter_if_not_declared(
60 node,
getName() +
".max_cost", rclcpp::ParameterValue(253.0));
61 max_cost_ =
static_cast<float>(node->get_parameter(
getName() +
".max_cost").as_double());
64 nav2::declare_parameter_if_not_declared(
65 node,
getName() +
".check_resolution", rclcpp::ParameterValue(1));
66 check_resolution_ =
static_cast<unsigned int>(
67 node->get_parameter(
getName() +
".check_resolution").as_int());
69 nav2::declare_parameter_if_not_declared(
70 node,
getName() +
".max_collision_dist", rclcpp::ParameterValue(5.0));
71 max_collision_dist_ =
static_cast<float>(
72 node->get_parameter(
getName() +
".max_collision_dist").as_double());
73 if (max_collision_dist_ <= 0.0) {
75 logger_,
"Max collision distance to evaluate is zero or negative, checking the full route.");
76 max_collision_dist_ = std::numeric_limits<float>::max();
83 costmap_ = costmap_subscriber_->getCostmap();
86 "Collision Monitor could not obtain a costmap from topic: " + topic_);
95 const geometry_msgs::msg::PoseStamped & curr_pose,
99 auto now = clock_->now();
100 if (now - last_check_time_ < checking_duration_ || !curr_edge) {
103 last_check_time_ = now;
108 float dist_checked = 0.0;
111 curr_pose, curr_edge->start->coords, end);
112 unsigned int curr_edge_id = curr_edge->edgeid;
114 bool final_edge =
false;
115 while (!final_edge) {
117 const float edge_dist = hypotf(end.x - start.x, end.y - start.y);
118 if (dist_checked + edge_dist >= max_collision_dist_) {
119 float dist_to_eval = max_collision_dist_ - dist_checked;
123 dist_checked += edge_dist;
138 logger_,
"Collision has been detected within %0.2fm of robot pose!", max_collision_dist_);
140 if (reroute_on_collision_) {
141 result.reroute =
true;
142 result.blocked_ids.push_back(curr_edge_id);
147 "Collision detected, but rerouting is not enabled, canceling tracking task.");
153 auto isCurrEdge = [&](
const EdgePtr & edge) {
return edge->edgeid == curr_edge_id;};
154 auto iter = std::find_if(route.edges.begin(), route.edges.end(), isCurrEdge);
155 if (iter != route.edges.end() && ++iter != route.edges.end()) {
157 curr_edge_id = (*iter)->edgeid;
158 end = (*iter)->end->coords;
172 const float dx = end.x - start.x;
173 const float dy = end.y - start.y;
174 const float mag = hypotf(dx, dy);
178 new_end.x = (dx / mag) * dist + start.x;
179 new_end.y = (dy / mag) * dist + start.y;
187 if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0)) {
193 unsigned int last_end_x = line.x0, last_end_y = line.y0;
195 int size_x =
static_cast<int>(costmap_->getSizeInCellsX());
196 int size_y =
static_cast<int>(costmap_->getSizeInCellsY());
198 if (iter.
getX() >= size_x || iter.
getY() >= size_y) {
199 line.x1 = last_end_x;
200 line.y1 = last_end_y;
203 last_end_x = iter.
getX();
204 last_end_y = iter.
getY();
213 if (!costmap_->worldToMap(start.x, start.y, line.x0, line.y0) ||
214 !costmap_->worldToMap(end.x, end.y, line.x1, line.y1))
225 float cost =
static_cast<float>(costmap_->getCost(iter.
getX(), iter.
getY()));
226 if (cost >= max_cost_ && cost != 255.0 ) {
231 for (
unsigned int i = 0; i < check_resolution_; i++) {
240 #include "pluginlib/class_list_macros.hpp"
A route operation to process a costmap to determine if a route is blocked requiring immediate rerouti...
std::string getName() override
Get name of the plugin for parameter scope mapping.
Coordinates backoutValidEndPoint(const Coordinates &start, const Coordinates &end, const float dist)
Backs out the end coordinate along the line segment start-end to length dist.
void configure(const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber > costmap_subscriber, const std::string &name) override
Configure.
bool lineToMap(const Coordinates &start, const Coordinates &end, LineSegment &line)
Converts a line segment start-end into a LineSegment struct in costmap frame.
bool isInCollision(const LineSegment &line)
Checks a line segment in costmap frame for validity.
void getCostmap()
Gets the latest costmap from the costmap subscriber.
OperationResult perform(NodePtr, EdgePtr curr_edge, EdgePtr, const Route &route, const geometry_msgs::msg::PoseStamped &curr_pose, const Metadata *) override
The main speed limit operation to adjust the maximum speed of the vehicle.
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
An iterator implementing Bresenham Ray-Tracing.
bool isValid() const
If the iterator is valid.
int getX() const
Get current X value.
void advance()
Advance iteration along the line.
int getY() const
Get current Y value.
An object to store Node coordinates in different frames.
An object representing edges between nodes.
An object to store the nodes in the graph file.
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.