Skip to content

Commit

Permalink
feat(motion_velocity_smoother): force slow driving (#1409)
Browse files Browse the repository at this point in the history
* add force slow driving function

Signed-off-by: Go Sakayori <[email protected]>

* fix state

Signed-off-by: Go Sakayori <[email protected]>

* erase log info

Signed-off-by: Go Sakayori <[email protected]>

---------

Signed-off-by: Go Sakayori <[email protected]>
Signed-off-by: Go Sakayori <[email protected]>
  • Loading branch information
go-sakayori committed Aug 6, 2024
1 parent e3b68d5 commit f122d37
Show file tree
Hide file tree
Showing 2 changed files with 41 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,12 @@ class VelocitySmootherNode : public rclcpp::Node
NORMAL = 3,
};

enum class ForceSlowDrivingType {
DEACTIVATED = 0,
READY = 1,
ACTIVATED = 2,
};

struct ForceAccelerationParam
{
double max_acceleration;
Expand Down Expand Up @@ -174,6 +180,7 @@ class VelocitySmootherNode : public rclcpp::Node
bool plan_from_ego_speed_on_manual_mode = true;

ForceAccelerationParam force_acceleration_param;
double force_slow_driving_velocity;
} node_param_{};

struct ExternalVelocityLimit
Expand Down Expand Up @@ -259,11 +266,16 @@ class VelocitySmootherNode : public rclcpp::Node

// parameter handling
void initCommonParam();

// Related to force acceleration
void onForceAcceleration(
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response);
bool force_acceleration_mode_;

// Related to force slow driving
void onSlowDriving(
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response);
ForceSlowDrivingType force_slow_driving_mode_;

// debug
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
Expand Down
30 changes: 29 additions & 1 deletion planning/autoware_velocity_smoother/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
srv_slow_driving_ = create_service<SetBool>(
"~/slow_driving", std::bind(&MotionVelocitySmootherNode::onSlowDriving, this, _1, _2));
force_acceleration_mode_ = false;
force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED;

// parameter update
set_param_res_ =
Expand Down Expand Up @@ -200,6 +201,7 @@ rcl_interfaces::msg::SetParametersResult VelocitySmootherNode::onParameter(
update_param("force_acceleration.engage_velocity", p.force_acceleration_param.engage_velocity);
update_param(
"force_acceleration.engage_acceleration", p.force_acceleration_param.engage_acceleration);
update_param("force_slow_driving.velocity", p.force_slow_driving_velocity);
}

{
Expand Down Expand Up @@ -329,6 +331,8 @@ void VelocitySmootherNode::initCommonParam()
declare_parameter<double>("force_acceleration.engage_velocity");
p.force_acceleration_param.engage_acceleration =
declare_parameter<double>("force_acceleration.engage_acceleration");

p.force_slow_driving_velocity = declare_parameter<double>("force_slow_driving.velocity");
}

void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const
Expand Down Expand Up @@ -502,6 +506,14 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr
flipVelocity(input_points);
}

// Only activate slow driving when velocity is below threshold
double slow_driving_vel_threshold = get_parameter("force_slow_driving.velocity").as_double();
if (
force_slow_driving_mode_ == ForceSlowDrivingType::READY &&
current_odometry_ptr_->twist.twist.linear.x < slow_driving_vel_threshold) {
force_slow_driving_mode_ = ForceSlowDrivingType::ACTIVATED;
}

const auto output = calcTrajectoryVelocity(input_points);
if (output.empty()) {
RCLCPP_WARN(get_logger(), "Output Point is empty");
Expand Down Expand Up @@ -591,6 +603,13 @@ TrajectoryPoints VelocitySmootherNode::calcTrajectoryVelocity(
// Apply velocity to approach stop point
applyStopApproachingVelocity(traj_extracted);

// Apply force slow driving if activated
if (force_slow_driving_mode_ == ForceSlowDrivingType::ACTIVATED) {
for (auto & tp : traj_extracted) {
tp.longitudinal_velocity_mps = get_parameter("force_slow_driving.velocity").as_double();
}
}

// Debug
if (publish_debug_trajs_) {
auto tmp = traj_extracted;
Expand Down Expand Up @@ -1172,12 +1191,21 @@ void MotionVelocitySmootherNode::onForceAcceleration(
}

response->success = true;
response->message = message;
}

void MotionVelocitySmootherNode::onSlowDriving(
const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response)
{
const std::string message = request->data ? "Slow driving" : "Default";
std::string message = "default";
if (request->data && force_slow_driving_mode_ == ForceSlowDrivingType::DEACTIVATED) {
force_slow_driving_mode_ = ForceSlowDrivingType::READY;

message = "Activated force slow drving";

Check warning on line 1204 in planning/autoware_velocity_smoother/src/node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (drving)
} else if (!request->data) {
force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED;
message = "Deactivated force slow driving";
}

response->success = true;
response->message = message;
Expand Down

0 comments on commit f122d37

Please sign in to comment.