-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Calculate next path point using lookahead for Graceful Controller #5003
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: main
Are you sure you want to change the base?
Changes from all commits
57d71ae
22e8e22
8242788
936c7da
96d3433
fa0535b
a660555
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||
---|---|---|---|---|---|---|---|---|
|
@@ -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" | ||||||||
|
||||||||
|
@@ -195,46 +196,35 @@ 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); | ||||||||
|
||||||||
// Work back from the end of plan to find valid target pose | ||||||||
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); | ||||||||
for (int i = transformed_plan.poses.size(); i >= 0; --i) { | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If you make this an There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. On making it unsigned int, There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @SakshayMahna There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I get this error:
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @SakshayMahna there are many solutions
|
||||||||
if (i == static_cast<int>(transformed_plan.poses.size())) { | ||||||||
// 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 | ||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||
target_pose = nav2_util::getLookAheadPoint(dist_to_target, transformed_plan, 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 | ||||||||
|
@@ -283,6 +273,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, | ||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I believe this will cause a minor regression - the getLookaheadPoint() function simply looks at the distance between the target point and the robot - not the distance ALONG the path. In some instances, this can lead to the controller massively shortcutting the desired path.
I would suggest making getLookaheadPoint use distance along path instead of hypot().
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Right!
I can make this change in this PR.
Or another issue/PR would be appropriate for this?
Uh oh!
There was an error while loading. Please reload this page.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think having it done here is important since that is a regression from the current behavior in this branch 😄
Also, it is a nice feature which RPP would also share in since they share the implementation! I know that's actually been a topic of conversion in other threads / tickets to add that feature, so I think that's wonderful to add in
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@SakshayMahna I believe this item is resolved, correct? @mikeferguson can you take another look?