471 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
472 nav2_core::GoalChecker * goal_checker)
476 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
483 nh_->get_logger(),
"[BackwardLocalPlanner] Current pose frame id: "
485 <<
", path pose frame id: " << pose.header.frame_id);
489 RCLCPP_ERROR_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] Inconsistent frames");
497 geometry_msgs::msg::Pose posetol;
498 geometry_msgs::msg::Twist twistol;
499 if (goal_checker->getTolerances(posetol, twistol))
506 nh_->get_logger(),
"[BackwardLocalPlanner] xy_goal_tolerance_: "
513 nh_->get_logger(),
"[BackwardLocalPlanner] could not get tolerances from goal checker");
519 "[BackwardLocalPlanner] ------------------- LOCAL PLANNER LOOP -----------------");
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;
530 "[BackwardLocalPlanner] missing robot pose, canceling compute Velocity Command");
532 bool divergenceDetected =
false;
534 bool emergency_stop =
false;
535 if (divergenceDetected)
538 nh_->get_logger(),
"[BackwardLocalPlanner] Divergence detected. Sending emergency stop.");
539 emergency_stop =
true;
543 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal created");
547 cmd_vel.twist.linear.x = 0;
548 cmd_vel.twist.angular.z = 0;
550 nh_->get_logger(),
"[BackwardLocalPlanner] emergency stop, exit compute commands");
556 double rho_error, betta_error, alpha_error;
560 tf2::convert(tfpose.pose.orientation, q);
565 const geometry_msgs::msg::PoseStamped & carrotgoalpose =
568 nh_->get_logger(),
"[BackwardLocalPlanner] carrot goal pose current index: "
571 const geometry_msgs::msg::Point & carrotGoalPosition = carrotgoalpose.pose.position;
573 tf2::Quaternion goalQ;
574 tf2::fromMsg(carrotgoalpose.pose.orientation, goalQ);
575 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] -- Control Policy --");
577 double betta = tf2::getYaw(goalQ);
578 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] goal orientation: " << betta);
581 double dx = carrotGoalPosition.x - tfpose.pose.position.x;
582 double dy = carrotGoalPosition.y - tfpose.pose.position.y;
585 rho_error = sqrt(dx * dx + dy * dy);
588 double theta = tf2::getYaw(q);
589 double alpha = atan2(dy, dx);
592 alpha_error = angles::shortest_angular_distance(alpha, theta);
593 betta_error = angles::shortest_angular_distance(betta, theta);
596 bool linearGoalReached;
597 bool currentPoseInGoal =
604 if (currentPoseInGoal && carrotInFinalGoalIndex)
610 "[BackwardLocalPlanner] GOAL REACHED. Send stop command and skipping trajectory collision: "
612 cmd_vel.twist.linear.x = 0;
613 cmd_vel.twist.angular.z = 0;
617 carrotInLinearGoalRange &&
632 tfpose, vetta, gamma, alpha_error, betta_error, rho_error);
637 vetta =
k_rho_ * rho_error;
646 "[BackwardLocalPlanner] we entered in a pure spinning state even in not pure-spining "
648 "carrotDistanceGoalReached: %d",
649 carrotInLinearGoalRange);
658 cmd_vel.twist.linear.x = vetta;
659 cmd_vel.twist.angular.z = gamma;
682 nh_->get_logger(),
"[BackwardLocalPlanner] local planner,"
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
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);
706 if (carrotHalfPlaneConstraintFailure)
710 "[BackwardLocalPlanner] CarrotHalfPlaneConstraintFailure detected. Sending "
711 "emergency stop and success to the planner.");
712 cmd_vel.twist.linear.x = 0;
720 geometry_msgs::msg::PoseStamped global_pose;
724 auto yaw = tf2::getYaw(global_pose.pose.orientation);
726 auto & pos = global_pose.pose.position;
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;
733 currentpose, currentvel, 0.8 , M_PI / 8 , 3.0 , 0.05 ,
737 bool acceptedLocalTrajectoryFreeOfObstacles =
true;
749 geometry_msgs::msg::Twist mockzerospeed;
751 for (
auto & p : trajectory)
763 float dx = p[0] - finalgoalpose.pose.position.x;
764 float dy = p[1] - finalgoalpose.pose.position.y;
766 float dst = sqrt(dx * dx + dy * dy);
771 "[BackwardLocalPlanner] trajectory simulation for collision checking: goal "
772 "reached with no collision");
776 costmap2d->worldToMap(p[0], p[1], mx, my);
787 if (costmap2d->getCost(mx, my) >= nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
789 acceptedLocalTrajectoryFreeOfObstacles =
false;
792 "[BackwardLocalPlanner] ABORTED LOCAL PLAN BECAUSE OBSTACLE DETEDTED at point "
793 << i <<
"/" << trajectory.size() << std::endl
794 << p[0] <<
", " << p[1]);
803 nh_->get_logger(),
"[BackwardLocalPlanner] Abort local - Backwards global plan size: %ld",
805 cmd_vel.twist.angular.z = 0;
806 cmd_vel.twist.linear.x = 0;
811 if (acceptedLocalTrajectoryFreeOfObstacles)
816 "[BackwardLocalPlanner] accepted local trajectory free of obstacle. Local planner "
824 cmd_vel.twist.linear.x = 0;
825 cmd_vel.twist.angular.z = 0;
832 nh_->get_logger(),
"[BackwardLocalPlanner][Not accepted local plan] starting countdown");
841 nh_->get_logger(),
"[BackwardLocalPlanner][Abort local] timeout! duration %lf/%f",
844 cmd_vel.twist.linear.x = 0;
845 cmd_vel.twist.angular.z = 0;
935 RCLCPP_INFO(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise");
940 "[BackwardLocalPlanner] resample precise skipping, size: " <<
backwardsPlanPath_.size());
950 RCLCPP_INFO_STREAM(
nh_->get_logger(),
"[BackwardLocalPlanner] resample precise, check: " << i);
954 tf2::Quaternion qCurrent, qNext;
955 tf2::convert(currpose.pose.orientation, qCurrent);
956 tf2::convert(nextpose.pose.orientation, qNext);
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);
962 bool resample =
false;
963 if (dist > maxallowedLinearError)
966 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, linear distance:"
967 << dist <<
"(" << maxallowedLinearError <<
")" << i);
972 double currentAngle = tf2::getYaw(qCurrent);
973 double nextAngle = tf2::getYaw(qNext);
975 double angularError = fabs(angles::shortest_angular_distance(currentAngle, nextAngle));
976 if (angularError > maxallowedAngularError)
980 nh_->get_logger(),
"[BackwardLocalPlanner] resampling point, angular distance:"
981 << angularError <<
"(" << maxallowedAngularError <<
")" << i);
987 geometry_msgs::msg::PoseStamped pintermediate;
988 auto duration = rclcpp::Time(nextpose.header.stamp) - rclcpp::Time(currpose.header.stamp);
990 pintermediate.header.frame_id = currpose.header.frame_id;
991 pintermediate.header.stamp = rclcpp::Time(currpose.header.stamp) + duration * 0.5;
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);
1008 nh_->get_logger(),
"[BackwardLocalPlanner] End resampling. resampled:" << counter
1009 <<
" new inserted poses "