Skip to content
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

- Modified findVelocitySignChange method to transform cusp into robot… #3036

Merged
merged 15 commits into from
Jun 23, 2022
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ class RegulatedPurePursuitController : public nav2_core::Controller
* @param pose Pose input to determine the cusp position
* @return robot distance from the cusp
*/
double findVelocitySignChange(const geometry_msgs::msg::PoseStamped & pose);
double findVelocitySignChange(const nav_msgs::msg::Path & transformed_plan);

/**
* Get the greatest extent of the costmap in meters from the center.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
// Check for reverse driving
if (allow_reversing_) {
// Cusp check
double dist_to_cusp = findVelocitySignChange(pose);
double dist_to_cusp = findVelocitySignChange(transformed_plan);

// if the lookahead distance is further than the cusp, use the cusp distance instead
if (dist_to_cusp < lookahead_dist) {
Expand Down Expand Up @@ -720,27 +720,29 @@ nav_msgs::msg::Path RegulatedPurePursuitController::transformGlobalPlan(
}

double RegulatedPurePursuitController::findVelocitySignChange(
const geometry_msgs::msg::PoseStamped & pose)
const nav_msgs::msg::Path & transformed_plan)
{
// Iterating through the global path to determine the position of the cusp
for (unsigned int pose_id = 1; pose_id < global_plan_.poses.size() - 1; ++pose_id) {
// Iterating through the transformed global path to determine the position of the cusp
for (unsigned int pose_id = 1; pose_id < transformed_plan.poses.size() - 1; ++pose_id) {
// We have two vectors for the dot product OA and AB. Determining the vectors.
double oa_x = global_plan_.poses[pose_id].pose.position.x -
global_plan_.poses[pose_id - 1].pose.position.x;
double oa_y = global_plan_.poses[pose_id].pose.position.y -
global_plan_.poses[pose_id - 1].pose.position.y;
double ab_x = global_plan_.poses[pose_id + 1].pose.position.x -
global_plan_.poses[pose_id].pose.position.x;
double ab_y = global_plan_.poses[pose_id + 1].pose.position.y -
global_plan_.poses[pose_id].pose.position.y;
double oa_x = transformed_plan.poses[pose_id].pose.position.x -
transformed_plan.poses[pose_id - 1].pose.position.x;
double oa_y = transformed_plan.poses[pose_id].pose.position.y -
transformed_plan.poses[pose_id - 1].pose.position.y;
double ab_x = transformed_plan.poses[pose_id + 1].pose.position.x -
transformed_plan.poses[pose_id].pose.position.x;
double ab_y = transformed_plan.poses[pose_id + 1].pose.position.y -
transformed_plan.poses[pose_id].pose.position.y;

/* Checking for the existance of cusp, in the path, using the dot product
and determine it's distance from the robot. If there is no cusp in the path,
then just determine the distance to the goal location. */
if ( (oa_x * ab_x) + (oa_y * ab_y) < 0.0) {
auto x = global_plan_.poses[pose_id].pose.position.x - pose.pose.position.x;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
auto y = global_plan_.poses[pose_id].pose.position.y - pose.pose.position.y;
return hypot(x, y); // returning the distance if there is a cusp
// returning the distance if there is a cusp
// The transformed path is in the robots frame, so robot is at the origin
return hypot(
transformed_plan.poses[pose_id].pose.position.x,
transformed_plan.poses[pose_id].pose.position.y);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,9 +103,9 @@ class BasicAPIRPP : public nav2_regulated_pure_pursuit_controller::RegulatedPure
}

double findVelocitySignChangeWrapper(
const geometry_msgs::msg::PoseStamped & pose)
const nav_msgs::msg::Path & transformed_plan)
{
return findVelocitySignChange(pose);
return findVelocitySignChange(transformed_plan);
}

nav_msgs::msg::Path transformGlobalPlanWrapper(
Expand Down Expand Up @@ -183,13 +183,15 @@ TEST(RegulatedPurePursuitTest, findVelocitySignChange)
path.poses[2].pose.position.x = -1.0;
path.poses[2].pose.position.y = -1.0;
ctrl->setPlan(path);
auto rtn = ctrl->findVelocitySignChangeWrapper(pose);
auto transformed_plan = ctrl->transformGlobalPlanWrapper(pose);
auto rtn = ctrl->findVelocitySignChangeWrapper(transformed_plan);
EXPECT_EQ(rtn, sqrt(5.0));

path.poses[2].pose.position.x = 3.0;
path.poses[2].pose.position.y = 3.0;
ctrl->setPlan(path);
rtn = ctrl->findVelocitySignChangeWrapper(pose);
transformed_plan = ctrl->transformGlobalPlanWrapper(pose);
rtn = ctrl->findVelocitySignChangeWrapper(transformed_plan);
EXPECT_EQ(rtn, std::numeric_limits<double>::max());
}

Expand Down