Skip to content
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,24 @@ class GracefulController : public nav2_core::Controller
void setSpeedLimit(const double & speed_limit, const bool & percentage) override;

protected:
/**
* @brief Validate a given target pose for calculating command velocity
* @param target_pose Target pose to validate
* @param dist_to_target Distance to target pose
* @param dist_to_goal Distance to navigation goal
* @param trajectory Trajectory to validate in simulation
* @param costmap_transform Transform between global and local costmap
* @param cmd_vel Initial command velocity to validate in simulation
* @return true if target pose is valid, false otherwise
*/
bool validateTargetPose(
geometry_msgs::msg::PoseStamped & target_pose,
double dist_to_target,
double dist_to_goal,
nav_msgs::msg::Path & trajectory,
geometry_msgs::msg::TransformStamped & costmap_transform,
geometry_msgs::msg::TwistStamped & cmd_vel);

/**
* @brief Simulate trajectory calculating in every step the new velocity command based on
* a new curvature value and checking for collisions.
Expand Down
104 changes: 70 additions & 34 deletions nav2_graceful_controller/src/graceful_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "angles/angles.h"
#include "nav2_core/controller_exceptions.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/controller_utils.hpp"
#include "nav2_graceful_controller/graceful_controller.hpp"
#include "nav2_costmap_2d/costmap_filters/filter_values.hpp"

Expand Down Expand Up @@ -195,46 +196,38 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
// Else, fall through and see if we should follow control law longer
}

// Precompute distance to candidate poses
// Find a valid target pose and its trajectory
nav_msgs::msg::Path local_plan;
geometry_msgs::msg::PoseStamped target_pose;

double dist_to_target;
std::vector<double> target_distances;
computeDistanceAlongPath(transformed_plan.poses, target_distances);
Comment thread
SakshayMahna marked this conversation as resolved.

// Work back from the end of plan to find valid target pose
bool is_first_iteration = true;
for (int i = transformed_plan.poses.size() - 1; i >= 0; --i) {
// Underlying control law needs a single target pose, which should:
// * Be as far away as possible from the robot (for smoothness)
// * But no further than the max_lookahed_ distance
// * Be feasible to reach in a collision free manner
geometry_msgs::msg::PoseStamped target_pose = transformed_plan.poses[i];
double dist_to_target = target_distances[i];

// Continue if target_pose is too far away from robot
if (dist_to_target > params_->max_lookahead) {continue;}

if (dist_to_goal < params_->max_lookahead) {
if (params_->prefer_final_rotation) {
// Avoid instability and big sweeping turns at the end of paths by
// ignoring final heading
double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x);
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
}
} else if (dist_to_target < params_->min_lookahead) {
// Make sure target is far enough away to avoid instability
break;
}

// Flip the orientation of the motion target if the robot is moving backwards
bool reversing = false;
if (params_->allow_backward && target_pose.pose.position.x < 0.0) {
reversing = true;
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
tf2::getYaw(target_pose.pose.orientation) + M_PI);
if (is_first_iteration) {
// Calculate target pose through lookahead interpolation to get most accurate
// lookahead point, if possible
dist_to_target = params_->max_lookahead;
// Interpolate after goal false for graceful controller
// Requires interpolating the orientation which is not yet implemented
Comment thread
SakshayMahna marked this conversation as resolved.
// Updates dist_to_target for target_pose returned if using the point on the path
target_pose = nav2_util::getLookAheadPoint(dist_to_target, transformed_plan, false);
is_first_iteration = false;
} else {
// Underlying control law needs a single target pose, which should:
// * Be as far away as possible from the robot (for smoothness)
// * But no further than the max_lookahed_ distance
// * Be feasible to reach in a collision free manner
dist_to_target = target_distances[i];
target_pose = transformed_plan.poses[i];
}

// Actually simulate our path
nav_msgs::msg::Path local_plan;
if (simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) {
// Successfully simulated to target_pose - compute velocity at this moment
// Compute velocity at this moment if valid target pose is found
if (validateTargetPose(
target_pose, dist_to_target, dist_to_goal, local_plan, costmap_transform, cmd_vel))
{
// Publish the selected target_pose
motion_target_pub_->publish(target_pose);
// Publish marker for slowdown radius around motion target for debugging / visualization
Expand Down Expand Up @@ -283,6 +276,49 @@ void GracefulController::setSpeedLimit(
}
}

bool GracefulController::validateTargetPose(
geometry_msgs::msg::PoseStamped & target_pose,
double dist_to_target,
double dist_to_goal,
nav_msgs::msg::Path & trajectory,
geometry_msgs::msg::TransformStamped & costmap_transform,
geometry_msgs::msg::TwistStamped & cmd_vel)
{
// Continue if target_pose is too far away from robot
if (dist_to_target > params_->max_lookahead) {
return false;
}

if (dist_to_goal < params_->max_lookahead) {
if (params_->prefer_final_rotation) {
// Avoid instability and big sweeping turns at the end of paths by
// ignoring final heading
double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x);
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
}
} else if (dist_to_target < params_->min_lookahead) {
// Make sure target is far enough away to avoid instability
return false;
}

// Flip the orientation of the motion target if the robot is moving backwards
bool reversing = false;
if (params_->allow_backward && target_pose.pose.position.x < 0.0) {
reversing = true;
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(
tf2::getYaw(target_pose.pose.orientation) + M_PI);
}

// Actually simulate the path
if (simulateTrajectory(target_pose, costmap_transform, trajectory, cmd_vel, reversing)) {
// Successfully simulated to target_pose
return true;
}

// Validation not successful
return false;
}

bool GracefulController::simulateTrajectory(
const geometry_msgs::msg::PoseStamped & motion_target,
const geometry_msgs::msg::TransformStamped & costmap_transform,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -174,32 +174,6 @@ class RegulatedPurePursuitController : public nav2_core::Controller
const double & pose_cost, const nav_msgs::msg::Path & path,
double & linear_vel, double & sign);

/**
* @brief Find the intersection a circle and a line segment.
* This assumes the circle is centered at the origin.
* If no intersection is found, a floating point error will occur.
* @param p1 first endpoint of line segment
* @param p2 second endpoint of line segment
* @param r radius of circle
* @return point of intersection
*/
static geometry_msgs::msg::Point circleSegmentIntersection(
const geometry_msgs::msg::Point & p1,
const geometry_msgs::msg::Point & p2,
double r);

/**
* @brief Get lookahead point
* @param lookahead_dist Optimal lookahead distance
* @param path Current global path
* @param interpolate_after_goal If true, interpolate the lookahead point after the goal based
* on the orientation given by the position of the last two pose of the path
* @return Lookahead point
*/
geometry_msgs::msg::PoseStamped getLookAheadPoint(
const double &, const nav_msgs::msg::Path &,
bool interpolate_after_goal = false);

/**
* @brief checks for the cusp position
* @param pose Pose input to determine the cusp position
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "nav2_core/controller_exceptions.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_util/controller_utils.hpp"
#include "nav2_costmap_2d/costmap_filters/filter_values.hpp"

using std::hypot;
Expand Down Expand Up @@ -204,7 +205,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
}

// Get the particular point on the path at the lookahead distance
auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan);
auto carrot_pose = nav2_util::getLookAheadPoint(lookahead_dist, transformed_plan);
auto rotate_to_path_carrot_pose = carrot_pose;
carrot_pub_->publish(createCarrotMsg(carrot_pose));

Expand All @@ -214,7 +215,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity

double regulation_curvature = lookahead_curvature;
if (params_->use_fixed_curvature_lookahead) {
auto curvature_lookahead_pose = getLookAheadPoint(
auto curvature_lookahead_pose = nav2_util::getLookAheadPoint(
curv_lookahead_dist,
transformed_plan, params_->interpolate_curvature_after_goal);
rotate_to_path_carrot_pose = curvature_lookahead_pose;
Expand Down Expand Up @@ -358,100 +359,6 @@ void RegulatedPurePursuitController::rotateToHeading(
}
}

geometry_msgs::msg::Point RegulatedPurePursuitController::circleSegmentIntersection(
const geometry_msgs::msg::Point & p1,
const geometry_msgs::msg::Point & p2,
double r)
{
// Formula for intersection of a line with a circle centered at the origin,
// modified to always return the point that is on the segment between the two points.
// https://mathworld.wolfram.com/Circle-LineIntersection.html
// This works because the poses are transformed into the robot frame.
// This can be derived from solving the system of equations of a line and a circle
// which results in something that is just a reformulation of the quadratic formula.
// Interactive illustration in doc/circle-segment-intersection.ipynb as well as at
// https://www.desmos.com/calculator/td5cwbuocd
double x1 = p1.x;
double x2 = p2.x;
double y1 = p1.y;
double y2 = p2.y;

double dx = x2 - x1;
double dy = y2 - y1;
double dr2 = dx * dx + dy * dy;
double D = x1 * y2 - x2 * y1;

// Augmentation to only return point within segment
double d1 = x1 * x1 + y1 * y1;
double d2 = x2 * x2 + y2 * y2;
double dd = d2 - d1;

geometry_msgs::msg::Point p;
double sqrt_term = std::sqrt(r * r * dr2 - D * D);
p.x = (D * dy + std::copysign(1.0, dd) * dx * sqrt_term) / dr2;
p.y = (-D * dx + std::copysign(1.0, dd) * dy * sqrt_term) / dr2;
return p;
}

geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoint(
const double & lookahead_dist,
const nav_msgs::msg::Path & transformed_plan,
bool interpolate_after_goal)
{
// Find the first pose which is at a distance greater than the lookahead distance
auto goal_pose_it = std::find_if(
transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](const auto & ps) {
return hypot(ps.pose.position.x, ps.pose.position.y) >= lookahead_dist;
});

// If the no pose is not far enough, take the last pose
if (goal_pose_it == transformed_plan.poses.end()) {
if (interpolate_after_goal) {
auto last_pose_it = std::prev(transformed_plan.poses.end());
auto prev_last_pose_it = std::prev(last_pose_it);

double end_path_orientation = atan2(
last_pose_it->pose.position.y - prev_last_pose_it->pose.position.y,
last_pose_it->pose.position.x - prev_last_pose_it->pose.position.x);

// Project the last segment out to guarantee it is beyond the look ahead
// distance
auto projected_position = last_pose_it->pose.position;
projected_position.x += cos(end_path_orientation) * lookahead_dist;
projected_position.y += sin(end_path_orientation) * lookahead_dist;

// Use the circle intersection to find the position at the correct look
// ahead distance
const auto interpolated_position = circleSegmentIntersection(
last_pose_it->pose.position, projected_position, lookahead_dist);

geometry_msgs::msg::PoseStamped interpolated_pose;
interpolated_pose.header = last_pose_it->header;
interpolated_pose.pose.position = interpolated_position;
return interpolated_pose;
} else {
goal_pose_it = std::prev(transformed_plan.poses.end());
}
} else if (goal_pose_it != transformed_plan.poses.begin()) {
// Find the point on the line segment between the two poses
// that is exactly the lookahead distance away from the robot pose (the origin)
// This can be found with a closed form for the intersection of a segment and a circle
// Because of the way we did the std::find_if, prev_pose is guaranteed to be inside the circle,
// and goal_pose is guaranteed to be outside the circle.
auto prev_pose_it = std::prev(goal_pose_it);
auto point = circleSegmentIntersection(
prev_pose_it->pose.position,
goal_pose_it->pose.position, lookahead_dist);
geometry_msgs::msg::PoseStamped pose;
pose.header.frame_id = prev_pose_it->header.frame_id;
pose.header.stamp = goal_pose_it->header.stamp;
pose.pose.position = point;
return pose;
}

return *goal_pose_it;
}

void RegulatedPurePursuitController::applyConstraints(
const double & curvature, const geometry_msgs::msg::Twist & /*curr_speed*/,
const double & pose_cost, const nav_msgs::msg::Path & path, double & linear_vel, double & sign)
Expand Down
Loading
Loading