Skip to content

Commit 38a8bc3

Browse files
committed
Add Interpolation Logic to Graceful Controller
Calculate Lookahead Point using Interpolation for Graceful Controller. Support both for in trajectory and goal extrapolation. - Add parameters for lookahead resolution and interpolate after goal. - Add logic to calculate lookahead point using interpolation. Goal Extrapolation can be switched on and off using `interpolate_after_goal` parameter.
1 parent eebf52a commit 38a8bc3

File tree

5 files changed

+169
-12
lines changed

5 files changed

+169
-12
lines changed

nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,32 @@ class GracefulController : public nav2_core::Controller
107107
void setSpeedLimit(const double & speed_limit, const bool & percentage) override;
108108

109109
protected:
110+
/**
111+
* @brief Find the intersection a circle and a line segment.
112+
* This assumes the circle is centered at the origin.
113+
* If no intersection is found, a floating point error will occur.
114+
* @param p1 first endpoint of line segment
115+
* @param p2 second endpoint of line segment
116+
* @param r radius of circle
117+
* @return point of intersection
118+
*/
119+
static geometry_msgs::msg::Point circleSegmentIntersection(
120+
const geometry_msgs::msg::Point & p1,
121+
const geometry_msgs::msg::Point & p2,
122+
double r);
123+
124+
/**
125+
* @brief Get lookahead point
126+
* @param lookahead_dist Optimal lookahead distance
127+
* @param path Current global path
128+
* @param interpolate_after_goal If true, interpolate the lookahead point after the goal based
129+
* on the orientation given by the position of the last two pose of the path
130+
* @return Lookahead point
131+
*/
132+
geometry_msgs::msg::PoseStamped getLookAheadPoint(
133+
const double &, const nav_msgs::msg::Path &,
134+
bool interpolate_after_goal = false);
135+
110136
/**
111137
* @brief Simulate trajectory calculating in every step the new velocity command based on
112138
* a new curvature value and checking for collisions.

nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,8 @@ struct Parameters
3535
double transform_tolerance;
3636
double min_lookahead;
3737
double max_lookahead;
38+
double lookahead_resolution;
39+
bool interpolate_after_goal;
3840
double max_robot_pose_search_dist;
3941
double k_phi;
4042
double k_delta;

nav2_graceful_controller/params/graceful_controller_params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,8 @@ controller_server:
110110
transform_tolerance: 0.1
111111
min_lookahead: 0.25
112112
max_lookahead: 1.0
113+
lookahead_resolution: 0.1
114+
interpolate_after_goal: true
113115
initial_rotation: true
114116
initial_rotation_threshold: 0.75
115117
prefer_final_rotation: true

nav2_graceful_controller/src/graceful_controller.cpp

Lines changed: 129 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -193,21 +193,19 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
193193
// Else, fall through and see if we should follow control law longer
194194
}
195195

196-
// Precompute distance to candidate poses
197-
std::vector<double> target_distances;
198-
computeDistanceAlongPath(transformed_plan.poses, target_distances);
196+
// Calculate pose for reducing lookaheads
197+
float lookahead = params_->max_lookahead;
199198

200-
// Work back from the end of plan to find valid target pose
201-
for (int i = transformed_plan.poses.size() - 1; i >= 0; --i) {
199+
while (lookahead > params_->min_lookahead) {
202200
// Underlying control law needs a single target pose, which should:
203201
// * Be as far away as possible from the robot (for smoothness)
204202
// * But no further than the max_lookahed_ distance
205203
// * Be feasible to reach in a collision free manner
206-
geometry_msgs::msg::PoseStamped target_pose = transformed_plan.poses[i];
207-
double dist_to_target = target_distances[i];
204+
geometry_msgs::msg::PoseStamped target_pose = getLookAheadPoint(
205+
lookahead, transformed_plan, params_->interpolate_after_goal);
208206

209-
// Continue if target_pose is too far away from robot
210-
if (dist_to_target > params_->max_lookahead) {continue;}
207+
// Reduce lookahead
208+
lookahead = lookahead - params_->lookahead_resolution;
211209

212210
if (dist_to_goal < params_->max_lookahead) {
213211
if (params_->prefer_final_rotation) {
@@ -216,9 +214,6 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
216214
double yaw = std::atan2(target_pose.pose.position.y, target_pose.pose.position.x);
217215
target_pose.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(yaw);
218216
}
219-
} else if (dist_to_target < params_->min_lookahead) {
220-
// Make sure target is far enough away to avoid instability
221-
break;
222217
}
223218

224219
// Flip the orientation of the motion target if the robot is moving backwards
@@ -281,6 +276,128 @@ void GracefulController::setSpeedLimit(
281276
}
282277
}
283278

279+
geometry_msgs::msg::Point GracefulController::circleSegmentIntersection(
280+
const geometry_msgs::msg::Point & p1,
281+
const geometry_msgs::msg::Point & p2,
282+
double r)
283+
{
284+
// Formula for intersection of a line with a circle centered at the origin,
285+
// modified to always return the point that is on the segment between the two points.
286+
// https://mathworld.wolfram.com/Circle-LineIntersection.html
287+
// This works because the poses are transformed into the robot frame.
288+
// This can be derived from solving the system of equations of a line and a circle
289+
// which results in something that is just a reformulation of the quadratic formula.
290+
// Interactive illustration in doc/circle-segment-intersection.ipynb as well as at
291+
// https://www.desmos.com/calculator/td5cwbuocd
292+
double x1 = p1.x;
293+
double x2 = p2.x;
294+
double y1 = p1.y;
295+
double y2 = p2.y;
296+
297+
double dx = x2 - x1;
298+
double dy = y2 - y1;
299+
double dr2 = dx * dx + dy * dy;
300+
double D = x1 * y2 - x2 * y1;
301+
302+
// Augmentation to only return point within segment
303+
double d1 = x1 * x1 + y1 * y1;
304+
double d2 = x2 * x2 + y2 * y2;
305+
double dd = d2 - d1;
306+
307+
geometry_msgs::msg::Point p;
308+
double sqrt_term = std::sqrt(r * r * dr2 - D * D);
309+
p.x = (D * dy + std::copysign(1.0, dd) * dx * sqrt_term) / dr2;
310+
p.y = (-D * dx + std::copysign(1.0, dd) * dy * sqrt_term) / dr2;
311+
return p;
312+
}
313+
314+
geometry_msgs::msg::PoseStamped GracefulController::getLookAheadPoint(
315+
const double & lookahead_dist,
316+
const nav_msgs::msg::Path & transformed_plan,
317+
bool interpolate_after_goal)
318+
{
319+
// Find the first pose which is at a distance greater than the lookahead distance
320+
auto goal_pose_it = std::find_if(
321+
transformed_plan.poses.begin(), transformed_plan.poses.end(), [&](const auto & ps) {
322+
return hypot(ps.pose.position.x, ps.pose.position.y) >= lookahead_dist;
323+
});
324+
325+
// If the no pose is not far enough, take the last pose
326+
if (goal_pose_it == transformed_plan.poses.end()) {
327+
if (interpolate_after_goal) {
328+
auto last_pose_it = std::prev(transformed_plan.poses.end());
329+
auto prev_last_pose_it = std::prev(last_pose_it);
330+
331+
double end_path_orientation = atan2(
332+
last_pose_it->pose.position.y - prev_last_pose_it->pose.position.y,
333+
last_pose_it->pose.position.x - prev_last_pose_it->pose.position.x);
334+
335+
// Project the last segment out to guarantee it is beyond the look ahead
336+
// distance
337+
auto projected_position = last_pose_it->pose.position;
338+
projected_position.x += cos(end_path_orientation) * lookahead_dist;
339+
projected_position.y += sin(end_path_orientation) * lookahead_dist;
340+
341+
// Use the circle intersection to find the position at the correct look
342+
// ahead distance
343+
const auto interpolated_position = circleSegmentIntersection(
344+
last_pose_it->pose.position, projected_position, lookahead_dist);
345+
346+
// Calculate orientation towards interpolated position
347+
// Convert yaw to quaternion
348+
double interpolated_yaw = atan2(
349+
interpolated_position.y - last_pose_it->pose.position.y,
350+
interpolated_position.x - last_pose_it->pose.position.x);
351+
352+
geometry_msgs::msg::Quaternion interpolated_orientation;
353+
interpolated_orientation.x = 0.0;
354+
interpolated_orientation.y = 0.0;
355+
interpolated_orientation.z = sin(interpolated_yaw / 2.0);
356+
interpolated_orientation.w = cos(interpolated_yaw / 2.0);
357+
358+
geometry_msgs::msg::PoseStamped interpolated_pose;
359+
interpolated_pose.header = last_pose_it->header;
360+
interpolated_pose.pose.position = interpolated_position;
361+
interpolated_pose.pose.orientation = interpolated_orientation;
362+
363+
return interpolated_pose;
364+
} else {
365+
goal_pose_it = std::prev(transformed_plan.poses.end());
366+
}
367+
} else if (goal_pose_it != transformed_plan.poses.begin()) {
368+
// Find the point on the line segment between the two poses
369+
// that is exactly the lookahead distance away from the robot pose (the origin)
370+
// This can be found with a closed form for the intersection of a segment and a circle
371+
// Because of the way we did the std::find_if, prev_pose is guaranteed to be inside the circle,
372+
// and goal_pose is guaranteed to be outside the circle.
373+
auto prev_pose_it = std::prev(goal_pose_it);
374+
auto point = circleSegmentIntersection(
375+
prev_pose_it->pose.position,
376+
goal_pose_it->pose.position, lookahead_dist);
377+
378+
// Calculate orientation towards interpolated position
379+
// Convert yaw to quaternion
380+
double yaw = atan2(
381+
point.y - prev_pose_it->pose.position.y,
382+
point.x - prev_pose_it->pose.position.x);
383+
384+
geometry_msgs::msg::Quaternion orientation;
385+
orientation.x = 0.0;
386+
orientation.y = 0.0;
387+
orientation.z = sin(yaw / 2.0);
388+
orientation.w = cos(yaw / 2.0);
389+
390+
geometry_msgs::msg::PoseStamped pose;
391+
pose.header.frame_id = prev_pose_it->header.frame_id;
392+
pose.header.stamp = goal_pose_it->header.stamp;
393+
pose.pose.position = point;
394+
pose.pose.orientation = orientation;
395+
return pose;
396+
}
397+
398+
return *goal_pose_it;
399+
}
400+
284401
bool GracefulController::simulateTrajectory(
285402
const geometry_msgs::msg::PoseStamped & motion_target,
286403
const geometry_msgs::msg::TransformStamped & costmap_transform,

nav2_graceful_controller/src/parameter_handler.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,10 @@ ParameterHandler::ParameterHandler(
4141
node, plugin_name_ + ".min_lookahead", rclcpp::ParameterValue(0.25));
4242
declare_parameter_if_not_declared(
4343
node, plugin_name_ + ".max_lookahead", rclcpp::ParameterValue(1.0));
44+
declare_parameter_if_not_declared(
45+
node, plugin_name_ + ".lookahead_resolution", rclcpp::ParameterValue(0.1));
46+
declare_parameter_if_not_declared(
47+
node, plugin_name_ + ".interpolate_after_goal", rclcpp::ParameterValue(false));
4448
declare_parameter_if_not_declared(
4549
node, plugin_name_ + ".max_robot_pose_search_dist",
4650
rclcpp::ParameterValue(costmap_size_x / 2.0));
@@ -74,6 +78,8 @@ ParameterHandler::ParameterHandler(
7478
node->get_parameter(plugin_name_ + ".transform_tolerance", params_.transform_tolerance);
7579
node->get_parameter(plugin_name_ + ".min_lookahead", params_.min_lookahead);
7680
node->get_parameter(plugin_name_ + ".max_lookahead", params_.max_lookahead);
81+
node->get_parameter(plugin_name_ + ".lookahead_resolution", params_.lookahead_resolution);
82+
node->get_parameter(plugin_name_ + ".interpolate_after_goal", params_.interpolate_after_goal);
7783
node->get_parameter(
7884
plugin_name_ + ".max_robot_pose_search_dist", params_.max_robot_pose_search_dist);
7985
if (params_.max_robot_pose_search_dist < 0.0) {
@@ -141,6 +147,8 @@ ParameterHandler::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
141147
params_.min_lookahead = parameter.as_double();
142148
} else if (name == plugin_name_ + ".max_lookahead") {
143149
params_.max_lookahead = parameter.as_double();
150+
} else if (name == plugin_name_ + ".lookahead_resolution") {
151+
params_.lookahead_resolution = parameter.as_double();
144152
} else if (name == plugin_name_ + ".k_phi") {
145153
params_.k_phi = parameter.as_double();
146154
} else if (name == plugin_name_ + ".k_delta") {
@@ -179,6 +187,8 @@ ParameterHandler::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
179187
params_.initial_rotation = parameter.as_bool();
180188
} else if (name == plugin_name_ + ".prefer_final_rotation") {
181189
params_.prefer_final_rotation = parameter.as_bool();
190+
} else if (name == plugin_name_ + ".interpolate_after_goal") {
191+
params_.interpolate_after_goal = parameter.as_bool();
182192
} else if (name == plugin_name_ + ".allow_backward") {
183193
if (params_.initial_rotation && parameter.as_bool()) {
184194
RCLCPP_WARN(

0 commit comments

Comments
 (0)