470 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
471 nav2_core::GoalChecker * goal_checker)
475 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
482 nh_->get_logger(),
"[BackwardLocalPlanner] Current pose frame id: "
484 <<
", path pose frame id: " << pose.header.frame_id);
488 RCLCPP_ERROR_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] Inconsistent frames");
496 geometry_msgs::msg::Pose posetol;
497 geometry_msgs::msg::Twist twistol;
498 if (goal_checker->getTolerances(posetol, twistol))
505 nh_->get_logger(),
"[BackwardLocalPlanner] xy_goal_tolerance_: "
512 nh_->get_logger(),
"[BackwardLocalPlanner] could not get tolerances from goal checker");
518 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
520 geometry_msgs::msg::TwistStamped cmd_vel;
521 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] LOCAL PLANNER LOOP");
522 geometry_msgs::msg::PoseStamped paux;
523 geometry_msgs::msg::PoseStamped tfpose;
529 "[BackwardLocalPlanner] missing robot pose, canceling compute Velocity Command");
531 bool divergenceDetected =
false;
533 bool emergency_stop =
false;
534 if (divergenceDetected)
537 nh_->get_logger(),
"[BackwardLocalPlanner] Divergence detected. Sending emergency stop.");
538 emergency_stop =
true;
542 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal created");
546 cmd_vel.twist.linear.x = 0;
547 cmd_vel.twist.angular.z = 0;
549 nh_->get_logger(),
"[BackwardLocalPlanner] emergency stop, exit compute commands");
555 double rho_error, betta_error, alpha_error;
559 tf2::convert(tfpose.pose.orientation, q);
564 const geometry_msgs::msg::PoseStamped & carrotgoalpose =
567 nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal pose current index: "
570 const geometry_msgs::msg::Point & carrotGoalPosition = carrotgoalpose.pose.position;
572 tf2::Quaternion goalQ;
573 tf2::fromMsg(carrotgoalpose.pose.orientation, goalQ);
574 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] -- Control Policy --");
576 double betta = tf2::getYaw(goalQ);
577 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] goal orientation: " << betta);
580 double dx = carrotGoalPosition.x - tfpose.pose.position.x;
581 double dy = carrotGoalPosition.y - tfpose.pose.position.y;
584 rho_error = sqrt(dx * dx + dy * dy);
587 double theta = tf2::getYaw(q);
588 double alpha = atan2(dy, dx);
591 alpha_error = angles::shortest_angular_distance(alpha, theta);
592 betta_error = angles::shortest_angular_distance(betta, theta);
595 bool linearGoalReached;
596 bool currentPoseInGoal =
603 if (currentPoseInGoal && carrotInFinalGoalIndex)
609 "[BackwardLocalPlanner] GOAL REACHED. Send stop command and skipping trajectory collision: "
611 cmd_vel.twist.linear.x = 0;
612 cmd_vel.twist.angular.z = 0;
616 carrotInLinearGoalRange &&
631 tfpose, vetta, gamma, alpha_error, betta_error, rho_error);
636 vetta =
k_rho_ * rho_error;
645 "[BackwardLocalPlanner] we entered in a pure spinning state even in not pure-spining "
647 "carrotDistanceGoalReached: %d",
648 carrotInLinearGoalRange);
657 cmd_vel.twist.linear.x = vetta;
658 cmd_vel.twist.angular.z = gamma;
681 nh_->get_logger(),
"[BackwardLocalPlanner] local planner,"
683 <<
" current pose in goal: " << currentPoseInGoal << std::endl
684 <<
" carrot in final goal index: " << carrotInFinalGoalIndex << std::endl
685 <<
" carrot in linear goal range: " << carrotInLinearGoalRange << std::endl
689 <<
" theta: " << theta << std::endl
690 <<
" betta: " << theta << std::endl
691 <<
" err_x: " << dx << std::endl
692 <<
" err_y:" << dy << std::endl
693 <<
" rho_error:" << rho_error << std::endl
694 <<
" alpha_error:" << alpha_error << std::endl
695 <<
" betta_error:" << betta_error << std::endl
696 <<
" vetta:" << vetta << std::endl
697 <<
" gamma:" << gamma << std::endl
698 <<
" cmd_vel.lin.x:" << cmd_vel.twist.linear.x << std::endl
699 <<
" cmd_vel.ang.z:" << cmd_vel.twist.angular.z);
705 if (carrotHalfPlaneConstraintFailure)
709 "[BackwardLocalPlanner] CarrotHalfPlaneConstraintFailure detected. Sending "
710 "emergency stop and success to the planner.");
711 cmd_vel.twist.linear.x = 0;
719 geometry_msgs::msg::PoseStamped global_pose;
723 auto yaw = tf2::getYaw(global_pose.pose.orientation);
725 auto & pos = global_pose.pose.position;
727 Eigen::Vector3f currentpose(pos.x, pos.y, yaw);
728 Eigen::Vector3f currentvel(
729 cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z);
730 std::vector<Eigen::Vector3f> trajectory;
732 currentpose, currentvel, 0.8 , M_PI / 8 , 3.0 , 0.05 ,
736 bool acceptedLocalTrajectoryFreeOfObstacles =
true;
748 geometry_msgs::msg::Twist mockzerospeed;
750 for (
auto & p : trajectory)
762 float dx = p[0] - finalgoalpose.pose.position.x;
763 float dy = p[1] - finalgoalpose.pose.position.y;
765 float dst = sqrt(dx * dx + dy * dy);
770 "[BackwardLocalPlanner] trajectory simulation for collision checking: goal "
771 "reached with no collision");
775 costmap2d->worldToMap(p[0], p[1], mx, my);
786 if (costmap2d->getCost(mx, my) >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
788 acceptedLocalTrajectoryFreeOfObstacles =
false;
791 "[BackwardLocalPlanner] ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED at point "
792 << i <<
"/" << trajectory.size() << std::endl
793 << p[0] <<
", " << p[1]);
802 nh_->get_logger(),
"[BackwardLocalPlanner] Abort local - Backwards global plan size: %ld",
804 cmd_vel.twist.angular.z = 0;
805 cmd_vel.twist.linear.x = 0;
810 if (acceptedLocalTrajectoryFreeOfObstacles)
815 "[BackwardLocalPlanner] accepted local trajectory free of obstacle. Local planner "
823 cmd_vel.twist.linear.x = 0;
824 cmd_vel.twist.angular.z = 0;
831 nh_->get_logger(),
"[BackwardLocalPlanner][Not accepted local plan] starting countdown");
840 nh_->get_logger(),
"[BackwardLocalPlanner][Abort local] timeout! duration %lf/%f",
843 cmd_vel.twist.linear.x = 0;
844 cmd_vel.twist.angular.z = 0;
934 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise");
939 "[BackwardLocalPlanner] resample precise skipping, size: " <<
backwardsPlanPath_.size());
949 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise, check: " << i);
953 tf2::Quaternion qCurrent, qNext;
954 tf2::convert(currpose.pose.orientation, qCurrent);
955 tf2::convert(nextpose.pose.orientation, qNext);
957 double dx = nextpose.pose.position.x - currpose.pose.position.x;
958 double dy = nextpose.pose.position.y - currpose.pose.position.y;
959 double dist = sqrt(dx * dx + dy * dy);
961 bool resample =
false;
962 if (dist > maxallowedLinearError)
965 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, linear distance:"
966 << dist <<
"(" << maxallowedLinearError <<
")" << i);
971 double currentAngle = tf2::getYaw(qCurrent);
972 double nextAngle = tf2::getYaw(qNext);
974 double angularError = fabs(angles::shortest_angular_distance(currentAngle, nextAngle));
975 if (angularError > maxallowedAngularError)
979 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, angular distance:"
980 << angularError <<
"(" << maxallowedAngularError <<
")" << i);
986 geometry_msgs::msg::PoseStamped pintermediate;
987 auto duration = rclcpp::Time(nextpose.header.stamp) - rclcpp::Time(currpose.header.stamp);
989 pintermediate.header.frame_id = currpose.header.frame_id;
990 pintermediate.header.stamp = rclcpp::Time(currpose.header.stamp) + duration * 0.5;
992 pintermediate.pose.position.x = 0.5 * (currpose.pose.position.x + nextpose.pose.position.x);
993 pintermediate.pose.position.y = 0.5 * (currpose.pose.position.y + nextpose.pose.position.y);
994 pintermediate.pose.position.z = 0.5 * (currpose.pose.position.z + nextpose.pose.position.z);
995 tf2::Quaternion intermediateQuat = tf2::slerp(qCurrent, qNext, 0.5);
996 pintermediate.pose.orientation = tf2::toMsg(intermediateQuat);
1007 nh_->get_logger(),
"[BackwardLocalPlanner] End resampling. resampled:" << counter
1008 <<
" new inserted poses "