Skip to content

Commit

Permalink
Add cancel_deceleration to RegulatedPurePursuitController
Browse files Browse the repository at this point in the history
Signed-off-by: Ramon Wijnands <ramon.wijnands@nobleo.nl>
  • Loading branch information
Rayman committed Mar 26, 2024
1 parent 6dad49c commit a80350f
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 0 deletions.
Expand Up @@ -53,6 +53,7 @@ struct Parameters
double curvature_lookahead_dist;
bool use_rotate_to_heading;
double max_angular_accel;
double cancel_deceleration;
double rotate_to_heading_min_angle;
bool allow_reversing;
double max_robot_pose_search_dist;
Expand Down
Expand Up @@ -96,6 +96,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller
const geometry_msgs::msg::Twist & velocity,
nav2_core::GoalChecker * /*goal_checker*/) override;

bool cancel() override;

/**
* @brief nav2_core setPlan - Sets the global plan
* @param path The global plan
Expand All @@ -111,6 +113,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller
*/
void setSpeedLimit(const double & speed_limit, const bool & percentage) override;

void reset() override;

protected:
/**
* @brief Get lookahead distance
Expand Down Expand Up @@ -212,6 +216,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller
Parameters * params_;
double goal_dist_tol_;
double control_duration_;
bool cancelling_ = false;
bool finished_cancelling_ = false;

std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
Expand Down
Expand Up @@ -85,6 +85,8 @@ ParameterHandler::ParameterHandler(
node, plugin_name_ + ".rotate_to_heading_min_angle", rclcpp::ParameterValue(0.785));
declare_parameter_if_not_declared(
node, plugin_name_ + ".max_angular_accel", rclcpp::ParameterValue(3.2));
declare_parameter_if_not_declared(
node, plugin_name_ + ".cancel_deceleration", rclcpp::ParameterValue(1.0));
declare_parameter_if_not_declared(
node, plugin_name_ + ".allow_reversing", rclcpp::ParameterValue(false));
declare_parameter_if_not_declared(
Expand Down Expand Up @@ -151,6 +153,7 @@ ParameterHandler::ParameterHandler(
node->get_parameter(
plugin_name_ + ".rotate_to_heading_min_angle", params_.rotate_to_heading_min_angle);
node->get_parameter(plugin_name_ + ".max_angular_accel", params_.max_angular_accel);
node->get_parameter(plugin_name_ + ".cancel_deceleration", params_.cancel_deceleration);
node->get_parameter(plugin_name_ + ".allow_reversing", params_.allow_reversing);
node->get_parameter(
plugin_name_ + ".max_robot_pose_search_dist",
Expand Down Expand Up @@ -237,6 +240,8 @@ ParameterHandler::dynamicParametersCallback(
params_.regulated_linear_scaling_min_speed = parameter.as_double();
} else if (name == plugin_name_ + ".max_angular_accel") {
params_.max_angular_accel = parameter.as_double();
} else if (name == plugin_name_ + ".cancel_deceleration") {
params_.cancel_deceleration = parameter.as_double();
} else if (name == plugin_name_ + ".rotate_to_heading_min_angle") {
params_.rotate_to_heading_min_angle = parameter.as_double();
}
Expand Down
Expand Up @@ -238,6 +238,23 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
linear_vel, x_vel_sign);

if (cancelling_) {
const double & dt = control_duration_;
linear_vel = speed.linear.x - x_vel_sign * dt * params_->cancel_deceleration;

if (x_vel_sign > 0) {
if (linear_vel <= 0) {
linear_vel = 0;
finished_cancelling_ = true;
}
} else {
if (linear_vel >= 0) {
linear_vel = 0;
finished_cancelling_ = true;
}
}
}

// Apply curvature to angular velocity after constraining linear velocity
angular_vel = linear_vel * regulation_curvature;
}
Expand All @@ -258,6 +275,12 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
return cmd_vel;
}

bool RegulatedPurePursuitController::cancel()
{
cancelling_ = true;
return finished_cancelling_;
}

bool RegulatedPurePursuitController::shouldRotateToPath(
const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
double & x_vel_sign)
Expand Down Expand Up @@ -445,6 +468,12 @@ void RegulatedPurePursuitController::setSpeedLimit(
}
}

void RegulatedPurePursuitController::reset()
{
cancelling_ = false;
finished_cancelling_ = false;
}

double RegulatedPurePursuitController::findVelocitySignChange(
const nav_msgs::msg::Path & transformed_plan)
{
Expand Down

0 comments on commit a80350f

Please sign in to comment.