SMACC2
Loading...
Searching...
No Matches
backward_local_planner.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <angles/angles.h>
24
25#include <boost/intrusive_ptr.hpp>
26#include <chrono>
27#include <nav_2d_utils/tf_help.hpp>
28#include <pluginlib/class_list_macros.hpp>
29#include <visualization_msgs/msg/marker_array.hpp>
30
31// register this planner as a BaseLocalPlanner plugin
32PLUGINLIB_EXPORT_CLASS(
34
35using namespace std::literals::chrono_literals;
36
37namespace cl_nav2z
38{
39namespace backward_local_planner
40{
47
54
56{
57 RCLCPP_INFO_STREAM(nh_->get_logger(), "activating controller BackwardLocalPlanner");
59
60 goalMarkerPublisher_->on_activate();
61 planPub_->on_activate();
62 backwardsPlanPath_.clear();
63}
64
66{
67 this->clearMarkers();
68 RCLCPP_WARN_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] deactivated");
69 planPub_->on_deactivate();
70 goalMarkerPublisher_->on_deactivate();
71}
72
74{
75 this->clearMarkers();
76 RCLCPP_WARN_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] cleanup");
77 this->backwardsPlanPath_.clear();
79}
80
87template <typename T>
88void tryGetOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::string param, T & value)
89{
90 if (!node->get_parameter(param, value))
91 {
92 node->set_parameter(rclcpp::Parameter(param, value));
93 }
94}
95
97 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
98 const std::shared_ptr<tf2_ros::Buffer> tf,
99 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
100{
101 this->costmapRos_ = costmap_ros;
102 // rclcpp::Node::SharedPtr nh("~/BackwardLocalPlanner");
103 this->nh_ = parent.lock();
104 this->name_ = name;
105 this->tf_ = tf;
106
107 k_rho_ = -1.0;
108 k_alpha_ = 0.5;
109 k_betta_ = -1.0; // set to zero means that orientation is not important
117 waitingTimeout_ = rclcpp::Duration(10s);
118
119 this->currentCarrotPoseIndex_ = 0;
120
122 nh_, name_ + ".pure_spinning_straight_line_mode", straightBackwardsAndPureSpinningMode_);
123
124 declareOrSet(nh_, name_ + ".k_rho", k_rho_);
125 declareOrSet(nh_, name_ + ".k_alpha", k_alpha_);
126 declareOrSet(nh_, name_ + ".k_betta", k_betta_);
127 declareOrSet(nh_, name_ + ".linear_mode_rho_error_threshold", linear_mode_rho_error_threshold_);
128
129 declareOrSet(nh_, name_ + ".carrot_distance", carrot_distance_);
130 declareOrSet(nh_, name_ + ".carrot_angular_distance", carrot_angular_distance_);
131 declareOrSet(nh_, name_ + ".enable_obstacle_checking", enable_obstacle_checking_);
132
133 declareOrSet(nh_, name_ + ".max_linear_x_speed", max_linear_x_speed_);
134 declareOrSet(nh_, name_ + ".max_angular_z_speed", max_angular_z_speed_);
135
136 // we have to do this, for example for the case we are refining the final orientation.
137 // check at some point if the carrot is reached in "goal linear distance", then we go into
138 // some automatic pure-spinning mode where we only update the orientation
139 // This means that if we reach the carrot with precision we go into pure spinning mode but we cannot
140 // leave that point (maybe this could be improved)
141
143 {
144 RCLCPP_WARN_STREAM(
145 nh_->get_logger(), "[BackwardLocalPlanner] carrot_angular_distance ("
147 << ") cannot be lower than yaw_goal_tolerance (" << yaw_goal_tolerance_
148 << ") setting carrot_angular_distance = " << yaw_goal_tolerance_);
150 }
151
153 {
154 RCLCPP_WARN_STREAM(
155 nh_->get_logger(), "[BackwardLocalPlanner] carrot_linear_distance ("
156 << carrot_distance_ << ") cannot be lower than xy_goal_tolerance_ ("
158 << ") setting carrot_angular_distance = " << xy_goal_tolerance_);
160 }
161
162 goalMarkerPublisher_ = nh_->create_publisher<visualization_msgs::msg::MarkerArray>(
163 "backward_local_planner/goal_marker", rclcpp::QoS(1));
164
165 planPub_ =
166 nh_->create_publisher<nav_msgs::msg::Path>("backward_local_planner/path", rclcpp::QoS(1));
167}
168
170{
171 RCLCPP_INFO_STREAM(nh_->get_logger(), "--- parameters ---");
172 tryGetOrSet(nh_, name_ + ".k_rho", k_rho_);
173 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".k_rho:" << k_rho_);
174 tryGetOrSet(nh_, name_ + ".k_alpha", k_alpha_);
175 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".k_alpha:" << k_alpha_);
176 tryGetOrSet(nh_, name_ + ".k_betta", k_betta_);
177 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".k_betta:" << k_betta_);
178
179 tryGetOrSet(nh_, name_ + ".enable_obstacle_checking", enable_obstacle_checking_);
180 RCLCPP_INFO_STREAM(
181 nh_->get_logger(), name_ + ".enable_obstacle_checking: " << enable_obstacle_checking_);
182
183 tryGetOrSet(nh_, name_ + ".carrot_distance", carrot_distance_);
184 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".carrot_distance:" << carrot_distance_);
185 tryGetOrSet(nh_, name_ + ".carrot_angular_distance", carrot_angular_distance_);
186 RCLCPP_INFO_STREAM(
187 nh_->get_logger(), name_ + ".carrot_angular_distance: " << carrot_angular_distance_);
188
190 nh_, name_ + ".pure_spinning_straight_line_mode", straightBackwardsAndPureSpinningMode_);
191 RCLCPP_INFO_STREAM(
192 nh_->get_logger(),
193 name_ + ".pure_spinning_straight_line_mode: " << straightBackwardsAndPureSpinningMode_);
194
195 tryGetOrSet(nh_, name_ + ".linear_mode_rho_error_threshold", linear_mode_rho_error_threshold_);
196 RCLCPP_INFO_STREAM(
197 nh_->get_logger(),
198 name_ + ".linear_mode_rho_error_threshold: " << linear_mode_rho_error_threshold_);
199 tryGetOrSet(nh_, name_ + ".max_linear_x_speed", max_linear_x_speed_);
200 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".max_linear_x_speed: " << max_linear_x_speed_);
201 tryGetOrSet(nh_, name_ + ".max_angular_z_speed", max_angular_z_speed_);
202 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".max_angular_z_speed: " << max_angular_z_speed_);
203
205 {
206 RCLCPP_WARN_STREAM(
207 nh_->get_logger(), "[BackwardLocalPlanner] carrot_angular_distance ("
209 << ") cannot be lower than yaw_goal_tolerance (" << yaw_goal_tolerance_
210 << ") setting carrot_angular_distance = " << yaw_goal_tolerance_);
212 nh_->set_parameter(
213 rclcpp::Parameter(name_ + ".carrot_angular_distance", carrot_angular_distance_));
214 }
215 RCLCPP_INFO_STREAM(
216 nh_->get_logger(), name_ + ".carrot_angular_distance: " << carrot_angular_distance_);
217
219 {
220 RCLCPP_WARN_STREAM(
221 nh_->get_logger(), "[BackwardLocalPlanner] carrot_linear_distance ("
222 << carrot_distance_ << ") cannot be lower than xy_goal_tolerance_ ("
224 << ") setting carrot_angular_distance = " << xy_goal_tolerance_);
226 nh_->set_parameter(rclcpp::Parameter(name_ + ".carrot_distance", carrot_distance_));
227 }
228 RCLCPP_INFO_STREAM(nh_->get_logger(), name_ + ".carrot_distance:" << carrot_distance_);
229 RCLCPP_INFO_STREAM(nh_->get_logger(), "--- end params ---");
230}
231
233 const double & /*speed_limit*/, const bool & /*percentage*/)
234{
235 RCLCPP_WARN_STREAM(
236 nh_->get_logger(),
237 "BackwardLocalPlanner::setSpeedLimit invoked. Ignored, funcionality not "
238 "implemented.");
239}
246 const geometry_msgs::msg::PoseStamped & tfpose, double & dist, double & angular_error)
247{
248 double angle = tf2::getYaw(tfpose.pose.orientation);
249 auto & carrot_pose = backwardsPlanPath_[currentCarrotPoseIndex_];
250 const geometry_msgs::msg::Point & carrot_point = carrot_pose.pose.position;
251
252 tf2::Quaternion carrot_orientation;
253 tf2::convert(carrot_pose.pose.orientation, carrot_orientation);
254 geometry_msgs::msg::Pose currentPoseDebugMsg = tfpose.pose;
255
256 // take error from the current position to the path point
257 double dx = carrot_point.x - tfpose.pose.position.x;
258 double dy = carrot_point.y - tfpose.pose.position.y;
259
260 dist = sqrt(dx * dx + dy * dy);
261
262 double pangle = tf2::getYaw(carrot_orientation);
263 angular_error = fabs(angles::shortest_angular_distance(pangle, angle));
264
265 RCLCPP_INFO_STREAM(
266 nh_->get_logger(), "[BackwardLocalPlanner] Compute carrot errors from current pose. (linear "
267 << dist << ")(angular " << angular_error << ")" << std::endl
268 << "Current carrot pose: " << std::endl
269 << carrot_pose << std::endl
270 << "Current actual pose:" << std::endl
271 << currentPoseDebugMsg);
272}
273
279bool BackwardLocalPlanner::updateCarrotGoal(const geometry_msgs::msg::PoseStamped & tfpose)
280{
281 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardsLocalPlanner] --- Carrot update ---");
282 double disterr = 0, angleerr = 0;
283 // iterate the point from the current position and backward until reaching a new goal point in the path
284 // this algorithm among other advantages has that skip the looping with an eager global planner
285 // that recalls the same plan (the already performed part of the plan in the current pose is skipped)
286 while (currentCarrotPoseIndex_ < (long)backwardsPlanPath_.size() - 1)
287 {
289
290 RCLCPP_INFO_STREAM(
291 nh_->get_logger(), "[BackwardsLocalPlanner] update carrot goal: Current index: "
292 << currentCarrotPoseIndex_ << "/" << backwardsPlanPath_.size());
293 RCLCPP_INFO(
294 nh_->get_logger(),
295 "[BackwardsLocalPlanner] update carrot goal: linear error %lf, angular error: %lf", disterr,
296 angleerr);
297
298 // target pose found, goal carrot tries to escape!
299 if (disterr < carrot_distance_ && angleerr < carrot_angular_distance_)
300 {
303 RCLCPP_INFO_STREAM(
304 nh_->get_logger(), "[BackwardsLocalPlanner] move carrot fw "
305 << currentCarrotPoseIndex_ << "/" << backwardsPlanPath_.size());
306 }
307 else
308 {
309 // carrot already escaped
310 break;
311 }
312 }
313 // RCLCPP_INFO(nh_->get_logger(),"[BackwardsLocalPlanner] computing angular error");
314 if (
315 currentCarrotPoseIndex_ >= (long)backwardsPlanPath_.size() - 1 && backwardsPlanPath_.size() > 0)
316 {
318 // reupdated errors
320 }
321
322 RCLCPP_INFO(
323 nh_->get_logger(), "[BackwardsLocalPlanner] Current index carrot goal: %d",
325 RCLCPP_INFO(
326 nh_->get_logger(),
327 "[BackwardsLocalPlanner] Update carrot goal: linear error %lf (xytol: %lf), angular error: "
328 "%lf",
329 disterr, xy_goal_tolerance_, angleerr);
330
331 bool carrotInGoalLinearRange = disterr < xy_goal_tolerance_;
332 RCLCPP_INFO(
333 nh_->get_logger(), "[BackwardsLocalPlanner] carrot in goal radius: %d",
334 carrotInGoalLinearRange);
335
336 RCLCPP_INFO(nh_->get_logger(), "[BackwardsLocalPlanner] ---End carrot update---");
337
338 return carrotInGoalLinearRange;
339}
340
342{
343 // this function should be called always the carrot is updated
344 divergenceDetectionLastCarrotLinearDistance_ = std::numeric_limits<double>::max();
345 return true;
346}
347
348bool BackwardLocalPlanner::divergenceDetectionUpdate(const geometry_msgs::msg::PoseStamped & tfpose)
349{
350 double disterr = 0, angleerr = 0;
352
353 RCLCPP_INFO_STREAM(
354 nh_->get_logger(), "[BackwardLocalPlanner] Divergence check. carrot goal distance. was: "
356 << ", now it is: " << disterr);
358 {
359 // candidate of divergence, we do not throw the divergence alarm yet
360 // but we neither update the distance since it is worse than the one
361 // we had previously with the same carrot.
362 const double MARGIN_FACTOR = 1.2;
363 if (disterr > MARGIN_FACTOR * divergenceDetectionLastCarrotLinearDistance_)
364 {
365 RCLCPP_ERROR_STREAM(
366 nh_->get_logger(),
367 "[BackwardLocalPlanner] Divergence detected. The same carrot goal distance was previously: "
368 << divergenceDetectionLastCarrotLinearDistance_ << "but now it is: " << disterr);
369 return true;
370 }
371 else
372 {
373 // divergence candidate
374 return false;
375 }
376 }
377 else
378 {
379 // update:
381 return false;
382 }
383}
384
386 const geometry_msgs::msg::PoseStamped & tfpose)
387{
388 // this function is specially useful when we want to reach the goal with a lot
389 // of precision. We may pass the goal and then the controller enters in some
390 // unstable state. With this, we are able to detect when stop moving.
391
392 // only apply if the carrot is in goal position and also if we are not in a pure spinning behavior v!=0
393
394 auto & carrot_pose = backwardsPlanPath_[currentCarrotPoseIndex_];
395 const geometry_msgs::msg::Point & carrot_point = carrot_pose.pose.position;
396 double yaw = tf2::getYaw(carrot_pose.pose.orientation);
397
398 // direction vector
399 double vx = cos(yaw);
400 double vy = sin(yaw);
401
402 // line implicit equation
403 // ax + by + c = 0
404 double c = -vx * carrot_point.x - vy * carrot_point.y;
405 const double C_OFFSET_METERS = 0.05; // 5 cm
406 double check = vx * tfpose.pose.position.x + vy * tfpose.pose.position.y + c + C_OFFSET_METERS;
407
408 RCLCPP_INFO_STREAM(
409 nh_->get_logger(),
410 "[BackwardLocalPlanner] half plane constraint:" << vx << "*" << carrot_point.x << " + " << vy
411 << "*" << carrot_point.y << " + " << c);
412 RCLCPP_INFO_STREAM(
413 nh_->get_logger(), "[BackwardLocalPlanner] constraint evaluation: "
414 << vx << "*" << tfpose.pose.position.x << " + " << vy << "*"
415 << tfpose.pose.position.y << " + " << c << " = " << check);
416
417 return check < 0;
418}
419
421 const geometry_msgs::msg::PoseStamped & tfpose,
422 const geometry_msgs::msg::Twist & /*currentTwist*/, double angle_error, bool & linearGoalReached,
423 nav2_core::GoalChecker * /*goal_checker*/)
424{
425 auto & finalgoal = backwardsPlanPath_.back();
426 double gdx = finalgoal.pose.position.x - tfpose.pose.position.x;
427 double gdy = finalgoal.pose.position.y - tfpose.pose.position.y;
428 double goaldist = sqrt(gdx * gdx + gdy * gdy);
429
430 auto abs_angle_error = fabs(angle_error);
431 // final_alpha_error =
432 RCLCPP_INFO_STREAM(
433 nh_->get_logger(), "[BackwardLocalPlanner] goal check. linear dist: "
434 << goaldist << "(" << this->xy_goal_tolerance_ << ")"
435 << ", angular dist: " << abs_angle_error << "("
436 << this->yaw_goal_tolerance_ << ")");
437
438 linearGoalReached = goaldist < this->xy_goal_tolerance_;
439
440 return linearGoalReached && abs_angle_error < this->yaw_goal_tolerance_;
441 // return goal_checker->isGoalReached(tfpose.pose, finalgoal.pose, currentTwist);
442}
443
450 const geometry_msgs::msg::PoseStamped & /*tfpose*/, double & vetta, double & gamma,
451 double alpha_error, double betta_error, double rho_error)
452{
453 if (rho_error > linear_mode_rho_error_threshold_) // works in straight motion mode
454 {
455 vetta = k_rho_ * rho_error;
456 gamma = k_alpha_ * alpha_error;
457 }
458 else if (fabs(betta_error) >= this->yaw_goal_tolerance_) // works in pure spinning mode
459 {
460 vetta = 0; // disable linear
461 gamma = k_betta_ * betta_error;
462 }
463}
464
470geometry_msgs::msg::TwistStamped BackwardLocalPlanner::computeVelocityCommands(
471 const geometry_msgs::msg::PoseStamped & pose, const geometry_msgs::msg::Twist & velocity,
472 nav2_core::GoalChecker * goal_checker)
473{
474 RCLCPP_INFO(
475 nh_->get_logger(),
476 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
477 this->updateParameters();
478
479 // consistency check
480 if (this->backwardsPlanPath_.size() > 0)
481 {
482 RCLCPP_INFO_STREAM(
483 nh_->get_logger(), "[BackwardLocalPlanner] Current pose frame id: "
484 << backwardsPlanPath_.front().header.frame_id
485 << ", path pose frame id: " << pose.header.frame_id);
486
487 if (backwardsPlanPath_.front().header.frame_id != pose.header.frame_id)
488 {
489 RCLCPP_ERROR_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] Inconsistent frames");
490 }
491 }
492
493 // xy_goal_tolerance and yaw_goal_tolerance are just used for logging proposes and clamping the carrot
494 // goal distance (parameter safety)
495 if (xy_goal_tolerance_ == -1 || yaw_goal_tolerance_ == -1)
496 {
497 geometry_msgs::msg::Pose posetol;
498 geometry_msgs::msg::Twist twistol;
499 if (goal_checker->getTolerances(posetol, twistol))
500 {
501 xy_goal_tolerance_ = posetol.position.x;
502 yaw_goal_tolerance_ = tf2::getYaw(posetol.orientation);
503 //xy_goal_tolerance_ = posetol.position.x * 0.35; // WORKAROUND ISSUE GOAL CHECKER NAV_CONTROLLER DIFF
504 //yaw_goal_tolerance_ = tf2::getYaw(posetol.orientation) * 0.35;
505 RCLCPP_INFO_STREAM(
506 nh_->get_logger(), "[BackwardLocalPlanner] xy_goal_tolerance_: "
508 << ", yaw_goal_tolerance_: " << yaw_goal_tolerance_);
509 }
510 else
511 {
512 RCLCPP_INFO_STREAM(
513 nh_->get_logger(), "[BackwardLocalPlanner] could not get tolerances from goal checker");
514 }
515 }
516
517 RCLCPP_INFO(
518 nh_->get_logger(),
519 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
520
521 geometry_msgs::msg::TwistStamped cmd_vel;
522 RCLCPP_INFO(nh_->get_logger(), "[BackwardLocalPlanner] LOCAL PLANNER LOOP");
523 geometry_msgs::msg::PoseStamped paux;
524 geometry_msgs::msg::PoseStamped tfpose;
525
526 if (!costmapRos_->getRobotPose(tfpose))
527 {
528 RCLCPP_ERROR(
529 nh_->get_logger(),
530 "[BackwardLocalPlanner] missing robot pose, canceling compute Velocity Command");
531 } // it is not working in the pure spinning reel example, maybe the hyperplane check is enough
532 bool divergenceDetected = false;
533
534 bool emergency_stop = false;
535 if (divergenceDetected)
536 {
537 RCLCPP_ERROR(
538 nh_->get_logger(), "[BackwardLocalPlanner] Divergence detected. Sending emergency stop.");
539 emergency_stop = true;
540 }
541
542 bool carrotInLinearGoalRange = updateCarrotGoal(tfpose);
543 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] carrot goal created");
544
545 if (emergency_stop)
546 {
547 cmd_vel.twist.linear.x = 0;
548 cmd_vel.twist.angular.z = 0;
549 RCLCPP_INFO_STREAM(
550 nh_->get_logger(), "[BackwardLocalPlanner] emergency stop, exit compute commands");
551 // return false;
552 return cmd_vel;
553 }
554
555 // ------ Evaluate the current context ----
556 double rho_error, betta_error, alpha_error;
557
558 // getting carrot goal information
559 tf2::Quaternion q;
560 tf2::convert(tfpose.pose.orientation, q);
561
562 RCLCPP_INFO_STREAM(
563 nh_->get_logger(), "[BackwardLocalPlanner] carrot goal: " << currentCarrotPoseIndex_ << "/"
564 << backwardsPlanPath_.size());
565 const geometry_msgs::msg::PoseStamped & carrotgoalpose =
567 RCLCPP_INFO_STREAM(
568 nh_->get_logger(), "[BackwardLocalPlanner] carrot goal pose current index: "
569 << currentCarrotPoseIndex_ << "/" << backwardsPlanPath_.size() << ": "
570 << carrotgoalpose);
571 const geometry_msgs::msg::Point & carrotGoalPosition = carrotgoalpose.pose.position;
572
573 tf2::Quaternion goalQ;
574 tf2::fromMsg(carrotgoalpose.pose.orientation, goalQ);
575 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] -- Control Policy --");
576 // goal orientation (global frame)
577 double betta = tf2::getYaw(goalQ);
578 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] goal orientation: " << betta);
579 betta = betta + betta_offset_;
580
581 double dx = carrotGoalPosition.x - tfpose.pose.position.x;
582 double dy = carrotGoalPosition.y - tfpose.pose.position.y;
583
584 // distance error to the targetpoint
585 rho_error = sqrt(dx * dx + dy * dy);
586
587 // heading to goal angle
588 double theta = tf2::getYaw(q);
589 double alpha = atan2(dy, dx);
590 alpha = alpha + alpha_offset_;
591
592 alpha_error = angles::shortest_angular_distance(alpha, theta);
593 betta_error = angles::shortest_angular_distance(betta, theta);
594 //------------- END CONTEXT EVAL ----------
595
596 bool linearGoalReached;
597 bool currentPoseInGoal =
598 checkCurrentPoseInGoalRange(tfpose, velocity, betta_error, linearGoalReached, goal_checker);
599
600 // Make sure the robot is very close to the goal and it is really in the the last goal point.
601 bool carrotInFinalGoalIndex = currentCarrotPoseIndex_ == (int)backwardsPlanPath_.size() - 1;
602
603 // checking if we are really in the end goal pose
604 if (currentPoseInGoal && carrotInFinalGoalIndex)
605 {
606 goalReached_ = true;
607 // backwardsPlanPath_.clear();
608 RCLCPP_INFO_STREAM(
609 nh_->get_logger(),
610 "[BackwardLocalPlanner] GOAL REACHED. Send stop command and skipping trajectory collision: "
611 << cmd_vel.twist);
612 cmd_vel.twist.linear.x = 0;
613 cmd_vel.twist.angular.z = 0;
614 return cmd_vel;
615 }
616 else if (
617 carrotInLinearGoalRange &&
618 linearGoalReached) // checking if we are in the end goal point but with incorrect
619 // orientation
620 {
621 // this means that we are not in the final angular distance, and we may even not be in the last carrot index
622 // (several intermediate angular poses until the last goal pose)
624 }
625
626 // --------------------
627 double vetta, gamma;
629 {
630 // decorated control rule for this mode
632 tfpose, vetta, gamma, alpha_error, betta_error, rho_error);
633 }
634 else // default free navigation backward motion mode
635 {
636 // regular control rule
637 vetta = k_rho_ * rho_error;
638 gamma = k_alpha_ * alpha_error + k_betta_ * betta_error;
639
640 // Even if we are in free navigation, we can enter in the pure spinning state.
641 // then, the linear motion is deactivated.
643 {
644 RCLCPP_INFO(
645 nh_->get_logger(),
646 "[BackwardLocalPlanner] we entered in a pure spinning state even in not pure-spining "
647 "configuration, "
648 "carrotDistanceGoalReached: %d",
649 carrotInLinearGoalRange);
650 gamma = k_betta_ * betta_error;
651 vetta = 0;
652 }
653
654 // classical control to reach a goal backwards
655 }
656
657 // Apply command and Clamp to limits
658 cmd_vel.twist.linear.x = vetta;
659 cmd_vel.twist.angular.z = gamma;
660
661 if (cmd_vel.twist.linear.x > max_linear_x_speed_)
662 {
663 cmd_vel.twist.linear.x = max_linear_x_speed_;
664 }
665 else if (cmd_vel.twist.linear.x < -max_linear_x_speed_)
666 {
667 cmd_vel.twist.linear.x = -max_linear_x_speed_;
668 }
669
670 if (cmd_vel.twist.angular.z > max_angular_z_speed_)
671 {
672 cmd_vel.twist.angular.z = max_angular_z_speed_;
673 }
674 else if (cmd_vel.twist.angular.z < -max_angular_z_speed_)
675 {
676 cmd_vel.twist.angular.z = -max_angular_z_speed_;
677 }
678
679 publishGoalMarker(carrotGoalPosition.x, carrotGoalPosition.y, betta);
680
681 RCLCPP_INFO_STREAM(
682 nh_->get_logger(), "[BackwardLocalPlanner] local planner,"
683 << std::endl
684 << " current pose in goal: " << currentPoseInGoal << std::endl
685 << " carrot in final goal index: " << carrotInFinalGoalIndex << std::endl
686 << " carrot in linear goal range: " << carrotInLinearGoalRange << std::endl
687 << " straightAnPureSpiningMode: " << straightBackwardsAndPureSpinningMode_
688 << std::endl
689 << " inGoalPureSpinningState: " << inGoalPureSpinningState_ << std::endl
690 << " theta: " << theta << std::endl
691 << " betta: " << theta << std::endl
692 << " err_x: " << dx << std::endl
693 << " err_y:" << dy << std::endl
694 << " rho_error:" << rho_error << std::endl
695 << " alpha_error:" << alpha_error << std::endl
696 << " betta_error:" << betta_error << std::endl
697 << " vetta:" << vetta << std::endl
698 << " gamma:" << gamma << std::endl
699 << " cmd_vel.lin.x:" << cmd_vel.twist.linear.x << std::endl
700 << " cmd_vel.ang.z:" << cmd_vel.twist.angular.z);
701
703 {
704 bool carrotHalfPlaneConstraintFailure = checkCarrotHalfPlainConstraint(tfpose);
705
706 if (carrotHalfPlaneConstraintFailure)
707 {
708 RCLCPP_ERROR(
709 nh_->get_logger(),
710 "[BackwardLocalPlanner] CarrotHalfPlaneConstraintFailure detected. Sending "
711 "emergency stop and success to the planner.");
712 cmd_vel.twist.linear.x = 0;
713 }
714 }
715
716 // ---------------------- TRAJECTORY PREDICTION AND COLLISION AVOIDANCE ---------------------
717 // cmd_vel.twist.linear.x=0;
718 // cmd_vel.twist.angular.z = 0;
719
720 geometry_msgs::msg::PoseStamped global_pose;
721 costmapRos_->getRobotPose(global_pose);
722
723 auto * costmap2d = costmapRos_->getCostmap();
724 auto yaw = tf2::getYaw(global_pose.pose.orientation);
725
726 auto & pos = global_pose.pose.position;
727
728 Eigen::Vector3f currentpose(pos.x, pos.y, yaw);
729 Eigen::Vector3f currentvel(
730 cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z);
731 std::vector<Eigen::Vector3f> trajectory;
732 this->generateTrajectory(
733 currentpose, currentvel, 0.8 /*meters*/, M_PI / 8 /*rads*/, 3.0 /*seconds*/, 0.05 /*seconds*/,
734 trajectory);
735
736 // check plan rejection
737 bool acceptedLocalTrajectoryFreeOfObstacles = true;
738
739 unsigned int mx, my;
740
742 {
743 if (backwardsPlanPath_.size() > 0)
744 {
745 auto & finalgoalpose = backwardsPlanPath_.back();
746
747 int i = 0;
748 // RCLCPP_INFO_STREAM(nh_->get_logger(), "lplanner goal: " << finalgoalpose.pose.position);
749 geometry_msgs::msg::Twist mockzerospeed;
750
751 for (auto & p : trajectory)
752 {
753 /*geometry_msgs::msg::Pose pg;
754 pg.position.x = p[0];
755 pg.position.y = p[1];
756 tf2::Quaternion q;
757 q.setRPY(0, 0, p[2]);
758 pg.orientation = tf2::toMsg(q);
759
760 // WARNING I CAN'T USE isGoalReached because I can change the state of a stateful goal checker
761 if (goal_checker->isGoalReached(pg, finalgoalpose.pose, mockzerospeed))*/
762
763 float dx = p[0] - finalgoalpose.pose.position.x;
764 float dy = p[1] - finalgoalpose.pose.position.y;
765
766 float dst = sqrt(dx * dx + dy * dy);
767 if (dst < xy_goal_tolerance_)
768 {
769 RCLCPP_INFO(
770 nh_->get_logger(),
771 "[BackwardLocalPlanner] trajectory simulation for collision checking: goal "
772 "reached with no collision");
773 break;
774 }
775
776 costmap2d->worldToMap(p[0], p[1], mx, my);
777 // unsigned int cost = costmap2d->getCost(mx, my);
778
779 // RCLCPP_INFO(nh_->get_logger(),"[BackwardLocalPlanner] checking cost pt %d [%lf, %lf] cell[%d,%d] = %d", i,
780 // p[0], p[1], mx, my, cost); RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] cost: " << cost);
781
782 // static const unsigned char NO_INFORMATION = 255;
783 // static const unsigned char LETHAL_OBSTACLE = 254;
784 // static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
785 // static const unsigned char FREE_SPACE = 0;
786
787 if (costmap2d->getCost(mx, my) >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
788 {
789 acceptedLocalTrajectoryFreeOfObstacles = false;
790 RCLCPP_WARN_STREAM(
791 nh_->get_logger(),
792 "[BackwardLocalPlanner] ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED at point "
793 << i << "/" << trajectory.size() << std::endl
794 << p[0] << ", " << p[1]);
795 break;
796 }
797 i++;
798 }
799 }
800 else
801 {
802 RCLCPP_WARN(
803 nh_->get_logger(), "[BackwardLocalPlanner] Abort local - Backwards global plan size: %ld",
804 backwardsPlanPath_.size());
805 cmd_vel.twist.angular.z = 0;
806 cmd_vel.twist.linear.x = 0;
807 // return false;
808 }
809 }
810
811 if (acceptedLocalTrajectoryFreeOfObstacles)
812 {
813 waiting_ = false;
814 RCLCPP_INFO(
815 nh_->get_logger(),
816 "[BackwardLocalPlanner] accepted local trajectory free of obstacle. Local planner "
817 "continues.");
818 return cmd_vel;
819 // return true;
820 }
821 else // that is not appceted because existence of obstacles
822 {
823 // emergency stop for collision: waiting a while before sending error
824 cmd_vel.twist.linear.x = 0;
825 cmd_vel.twist.angular.z = 0;
826
827 if (waiting_ == false)
828 {
829 waiting_ = true;
830 waitingStamp_ = nh_->now();
831 RCLCPP_WARN(
832 nh_->get_logger(), "[BackwardLocalPlanner][Not accepted local plan] starting countdown");
833 }
834 else
835 {
836 auto waitingduration = nh_->now() - waitingStamp_;
837
838 if (waitingduration > this->waitingTimeout_)
839 {
840 RCLCPP_WARN(
841 nh_->get_logger(), "[BackwardLocalPlanner][Abort local] timeout! duration %lf/%f",
842 waitingduration.seconds(), waitingTimeout_.seconds());
843 // return false;
844 cmd_vel.twist.linear.x = 0;
845 cmd_vel.twist.angular.z = 0;
846 return cmd_vel;
847 }
848 }
849
850 return cmd_vel;
851 }
852}
853
860{
861 RCLCPP_INFO(nh_->get_logger(), "[BackwardLocalPlanner] isGoalReached call");
862 return goalReached_;
863}
864
865bool BackwardLocalPlanner::findInitialCarrotGoal(geometry_msgs::msg::PoseStamped & tfpose)
866{
867 double lineardisterr, angleerr;
868 bool inCarrotRange = false;
869
870 // initial state check
871 computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, lineardisterr, angleerr);
872
873 // double minpointdist = std::numeric_limits<double>::max();
874
875 // lets set the carrot-goal in the correct place with this loop
876 while (currentCarrotPoseIndex_ < (int)backwardsPlanPath_.size() && !inCarrotRange)
877 {
878 computeCurrentEuclideanAndAngularErrorsToCarrotGoal(tfpose, lineardisterr, angleerr);
879
880 RCLCPP_INFO(
881 nh_->get_logger(),
882 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - error to carrot, linear = %lf "
883 "(%lf), "
884 "angular : %lf (%lf)",
886
887 // current path point is inside the carrot distance range, goal carrot tries to escape!
888 if (lineardisterr < carrot_distance_ && angleerr < carrot_angular_distance_)
889 {
890 RCLCPP_INFO(
891 nh_->get_logger(),
892 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - in carrot Range",
894 inCarrotRange = true;
895 // we are inside the goal range
896 }
897 else if (
898 inCarrotRange && (lineardisterr > carrot_distance_ || angleerr > carrot_angular_distance_))
899 {
900 // we were inside the carrot range but not anymore, now we are just leaving. we want to continue forward
901 // (currentCarrotPoseIndex_++) unless we go out of the carrot range
902
903 // but we rollback last index increment (to go back inside the carrot goal scope) and start motion with that
904 // carrot goal we found
906 break;
907 }
908 else
909 {
910 RCLCPP_INFO(
911 nh_->get_logger(),
912 "[BackwardLocalPlanner] Finding initial carrot goal i=%d - carrot out of range, searching "
913 "coincidence...",
915 }
916
918 RCLCPP_INFO_STREAM(
919 nh_->get_logger(), "[BackwardLocalPlanner] setPlan: fw" << currentCarrotPoseIndex_);
920 }
921
922 RCLCPP_INFO_STREAM(
923 nh_->get_logger(), "[BackwardLocalPlanner] setPlan: (found first carrot:"
924 << inCarrotRange << ") initial carrot point index: "
925 << currentCarrotPoseIndex_ << "/" << backwardsPlanPath_.size());
926
927 return inCarrotRange;
928}
929
931{
932 // this algorithm is really important to have a precise carrot (linear or angular)
933 // and not being considered as a divergence from the path
934
935 RCLCPP_INFO(nh_->get_logger(), "[BackwardLocalPlanner] resample precise");
936 if (backwardsPlanPath_.size() <= 1)
937 {
938 RCLCPP_INFO_STREAM(
939 nh_->get_logger(),
940 "[BackwardLocalPlanner] resample precise skipping, size: " << backwardsPlanPath_.size());
941 return false;
942 }
943
944 int counter = 0;
945 double maxallowedAngularError = 0.45 * this->carrot_angular_distance_; // nyquist
946 double maxallowedLinearError = 0.45 * this->carrot_distance_; // nyquist
947
948 for (int i = 0; i < (int)backwardsPlanPath_.size() - 1; i++)
949 {
950 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] resample precise, check: " << i);
951 auto & currpose = backwardsPlanPath_[i];
952 auto & nextpose = backwardsPlanPath_[i + 1];
953
954 tf2::Quaternion qCurrent, qNext;
955 tf2::convert(currpose.pose.orientation, qCurrent);
956 tf2::convert(nextpose.pose.orientation, qNext);
957
958 double dx = nextpose.pose.position.x - currpose.pose.position.x;
959 double dy = nextpose.pose.position.y - currpose.pose.position.y;
960 double dist = sqrt(dx * dx + dy * dy);
961
962 bool resample = false;
963 if (dist > maxallowedLinearError)
964 {
965 RCLCPP_INFO_STREAM(
966 nh_->get_logger(), "[BackwardLocalPlanner] resampling point, linear distance:"
967 << dist << "(" << maxallowedLinearError << ")" << i);
968 resample = true;
969 }
970 else
971 {
972 double currentAngle = tf2::getYaw(qCurrent);
973 double nextAngle = tf2::getYaw(qNext);
974
975 double angularError = fabs(angles::shortest_angular_distance(currentAngle, nextAngle));
976 if (angularError > maxallowedAngularError)
977 {
978 resample = true;
979 RCLCPP_INFO_STREAM(
980 nh_->get_logger(), "[BackwardLocalPlanner] resampling point, angular distance:"
981 << angularError << "(" << maxallowedAngularError << ")" << i);
982 }
983 }
984
985 if (resample)
986 {
987 geometry_msgs::msg::PoseStamped pintermediate;
988 auto duration = rclcpp::Time(nextpose.header.stamp) - rclcpp::Time(currpose.header.stamp);
989
990 pintermediate.header.frame_id = currpose.header.frame_id;
991 pintermediate.header.stamp = rclcpp::Time(currpose.header.stamp) + duration * 0.5;
992
993 pintermediate.pose.position.x = 0.5 * (currpose.pose.position.x + nextpose.pose.position.x);
994 pintermediate.pose.position.y = 0.5 * (currpose.pose.position.y + nextpose.pose.position.y);
995 pintermediate.pose.position.z = 0.5 * (currpose.pose.position.z + nextpose.pose.position.z);
996 tf2::Quaternion intermediateQuat = tf2::slerp(qCurrent, qNext, 0.5);
997 pintermediate.pose.orientation = tf2::toMsg(intermediateQuat);
998
999 this->backwardsPlanPath_.insert(this->backwardsPlanPath_.begin() + i + 1, pintermediate);
1000
1001 // retry this point
1002 i--;
1003 counter++;
1004 }
1005 }
1006
1007 RCLCPP_INFO_STREAM(
1008 nh_->get_logger(), "[BackwardLocalPlanner] End resampling. resampled:" << counter
1009 << " new inserted poses "
1010 "during precise "
1011 "resmapling.");
1012 return true;
1013}
1014
1020void BackwardLocalPlanner::setPlan(const nav_msgs::msg::Path & path)
1021{
1022 RCLCPP_INFO_STREAM(
1023 nh_->get_logger(),
1024 "[BackwardLocalPlanner] setPlan: new global plan received ( " << path.poses.size() << ")");
1025
1026 //------------- TRANSFORM TO LOCAL FRAME PATH ---------------------------
1027 nav_msgs::msg::Path transformedPlan;
1028 rclcpp::Duration ttol = rclcpp::Duration::from_seconds(transform_tolerance_);
1029 // transform global plan to the navigation reference frame
1030 for (auto & p : path.poses)
1031 {
1032 geometry_msgs::msg::PoseStamped transformedPose;
1033 nav_2d_utils::transformPose(tf_, costmapRos_->getGlobalFrameID(), p, transformedPose, ttol);
1034 transformedPose.header.frame_id = costmapRos_->getGlobalFrameID();
1035 transformedPlan.poses.push_back(transformedPose);
1036 }
1037
1038 backwardsPlanPath_ = transformedPlan.poses;
1039
1040 // --------- resampling path feature -----------
1041 geometry_msgs::msg::PoseStamped tfpose;
1042 if (!costmapRos_->getRobotPose(tfpose))
1043 {
1044 RCLCPP_ERROR(nh_->get_logger(), "Failure getting pose from Backward local planner");
1045 return;
1046 }
1047
1048 geometry_msgs::msg::PoseStamped posestamped = tfpose;
1049 backwardsPlanPath_.insert(backwardsPlanPath_.begin(), posestamped);
1050 this->resamplePrecisePlan();
1051
1052 nav_msgs::msg::Path planMsg;
1053 planMsg.poses = backwardsPlanPath_;
1054 planMsg.header.frame_id = costmapRos_->getGlobalFrameID();
1055 planMsg.header.stamp = nh_->now();
1056 planPub_->publish(planMsg);
1057
1058 // ------ reset controller state ----------------------
1059 goalReached_ = false;
1063
1064 if (path.poses.size() == 0)
1065 {
1066 RCLCPP_INFO_STREAM(nh_->get_logger(), "[BackwardLocalPlanner] received plan without any pose");
1067 // return true;
1068 return;
1069 }
1070
1071 // -------- initialize carrot ----------------
1072 bool foundInitialCarrotGoal = this->findInitialCarrotGoal(tfpose);
1073 if (!foundInitialCarrotGoal)
1074 {
1075 RCLCPP_ERROR(
1076 nh_->get_logger(),
1077 "[BackwardLocalPlanner] new plan rejected. The initial point in the global path is "
1078 "too much far away from the current state (according to carrot_distance "
1079 "parameter)");
1080 // return false; // in this case, the new plan broke the current execution
1081 return;
1082 }
1083 else
1084 {
1085 this->divergenceDetectionUpdate(tfpose);
1086 // SANDARD AND PREFERRED CASE ON NEW PLAN
1087 // return true;
1088 return;
1089 }
1090}
1091
1093 const Eigen::Vector3f & pos, const Eigen::Vector3f & vel, float maxdist, float maxanglediff,
1094 float maxtime, float dt, std::vector<Eigen::Vector3f> & outtraj)
1095{
1096 // simulate the trajectory and check for collisions, updating costs along the way
1097 bool end = false;
1098 float time = 0;
1099 Eigen::Vector3f currentpos = pos;
1100 int i = 0;
1101 while (!end)
1102 {
1103 // add the point to the trajectory so we can draw it later if we want
1104 // traj.addPoint(pos[0], pos[1], pos[2]);
1105
1106 // if (continued_acceleration_) {
1107 // //calculate velocities
1108 // loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt);
1109 // //RCLCPP_WARN_NAMED(nh_->get_logger(), "Generator", "Flag: %d, Loop_Vel %f, %f, %f", continued_acceleration_,
1110 // loop_vel[0], loop_vel[1], loop_vel[2]);
1111 // }
1112
1113 auto loop_vel = vel;
1114 // update the position of the robot using the velocities passed in
1115 auto newpos = computeNewPositions(currentpos, loop_vel, dt);
1116
1117 auto dx = newpos[0] - currentpos[0];
1118 auto dy = newpos[1] - currentpos[1];
1119 float dist, angledist;
1120
1121 // RCLCPP_INFO(nh_->get_logger(), "traj point %d", i);
1122 dist = sqrt(dx * dx + dy * dy);
1123 if (dist > maxdist)
1124 {
1125 end = true;
1126 // RCLCPP_INFO(nh_->get_logger(), "dist break: %f", dist);
1127 }
1128 else
1129 {
1130 // ouble from, double to
1131 angledist = angles::shortest_angular_distance(currentpos[2], newpos[2]);
1132 if (angledist > maxanglediff)
1133 {
1134 end = true;
1135 // RCLCPP_INFO(nh_->get_logger(), "angle dist break: %f", angledist);
1136 }
1137 else
1138 {
1139 outtraj.push_back(newpos);
1140
1141 time += dt;
1142 if (time > maxtime)
1143 {
1144 end = true;
1145 // RCLCPP_INFO(nh_->get_logger(), "time break: %f", time);
1146 }
1147
1148 // RCLCPP_INFO(nh_->get_logger(), "dist: %f, angledist: %f, time: %f", dist, angledist, time);
1149 }
1150 }
1151
1152 currentpos = newpos;
1153 i++;
1154 } // end for simulation steps
1155}
1156
1158 const Eigen::Vector3f & pos, const Eigen::Vector3f & vel, double dt)
1159{
1160 Eigen::Vector3f new_pos = Eigen::Vector3f::Zero();
1161 new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt;
1162 new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt;
1163 new_pos[2] = pos[2] + vel[2] * dt;
1164 return new_pos;
1165}
1166
1168{
1169 visualization_msgs::msg::Marker marker;
1170 marker.header.frame_id = this->costmapRos_->getGlobalFrameID();
1171 marker.header.stamp = nh_->now();
1172
1173 marker.ns = "my_namespace2";
1174 marker.id = 0;
1175 marker.type = visualization_msgs::msg::Marker::ARROW;
1176 marker.action = visualization_msgs::msg::Marker::DELETEALL;
1177
1178 visualization_msgs::msg::MarkerArray ma;
1179 ma.markers.push_back(marker);
1180
1181 goalMarkerPublisher_->publish(ma);
1182}
1183
1189void BackwardLocalPlanner::publishGoalMarker(double x, double y, double phi)
1190{
1191 visualization_msgs::msg::Marker marker;
1192 marker.header.frame_id = this->costmapRos_->getGlobalFrameID();
1193 marker.header.stamp = nh_->now();
1194
1195 marker.ns = "my_namespace2";
1196 marker.id = 0;
1197 marker.type = visualization_msgs::msg::Marker::ARROW;
1198 marker.action = visualization_msgs::msg::Marker::ADD;
1199 marker.lifetime = rclcpp::Duration(1.0s);
1200
1201 marker.pose.orientation.w = 1;
1202
1203 marker.scale.x = 0.05;
1204 marker.scale.y = 0.15;
1205 marker.scale.z = 0.05;
1206 marker.color.a = 1.0;
1207
1208 // red marker
1209 marker.color.r = 1;
1210 marker.color.g = 0;
1211 marker.color.b = 0;
1212
1213 geometry_msgs::msg::Point start, end;
1214 start.x = x;
1215 start.y = y;
1216
1217 end.x = x + 0.5 * cos(phi);
1218 end.y = y + 0.5 * sin(phi);
1219
1220 marker.points.push_back(start);
1221 marker.points.push_back(end);
1222
1223 visualization_msgs::msg::MarkerArray ma;
1224 ma.markers.push_back(marker);
1225
1226 goalMarkerPublisher_->publish(ma);
1227}
1228} // namespace backward_local_planner
1229} // namespace cl_nav2z
bool updateCarrotGoal(const geometry_msgs::msg::PoseStamped &pose)
bool checkCarrotHalfPlainConstraint(const geometry_msgs::msg::PoseStamped &pose)
Eigen::Vector3f computeNewPositions(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, double dt)
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *goal_checker) override
nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity
void straightBackwardsAndPureSpinCmd(const geometry_msgs::msg::PoseStamped &pose, double &vetta, double &gamma, double alpha_error, double betta_error, double rho_error)
std::vector< geometry_msgs::msg::PoseStamped > backwardsPlanPath_
void generateTrajectory(const Eigen::Vector3f &pos, const Eigen::Vector3f &vel, float maxdist, float maxangle, float maxtime, float dt, std::vector< Eigen::Vector3f > &outtraj)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< visualization_msgs::msg::MarkerArray > > goalMarkerPublisher_
bool findInitialCarrotGoal(geometry_msgs::msg::PoseStamped &pose)
bool divergenceDetectionUpdate(const geometry_msgs::msg::PoseStamped &pose)
void setPlan(const nav_msgs::msg::Path &path) override
nav2_core setPlan - Sets the global plan
void computeCurrentEuclideanAndAngularErrorsToCarrotGoal(const geometry_msgs::msg::PoseStamped &pose, double &dist, double &angular_error)
bool checkCurrentPoseInGoalRange(const geometry_msgs::msg::PoseStamped &tfpose, const geometry_msgs::msg::Twist &currentTwist, double angle_error, bool &linearGoalReached, nav2_core::GoalChecker *goalChecker)
std::shared_ptr< rclcpp_lifecycle::LifecyclePublisher< nav_msgs::msg::Path > > planPub_
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, const std::shared_ptr< tf2_ros::Buffer > tf, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmapRos_
void declareOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)
Definition common.hpp:34
void tryGetOrSet(rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string param, T &value)