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

feat(motion_velocity_smoother): force slow driving #1409

Merged
merged 3 commits into from
Jul 11, 2024
Merged
Show file tree
Hide file tree
Changes from all 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 @@ -132,6 +132,12 @@ class MotionVelocitySmootherNode : public rclcpp::Node
NORMAL = 3,
};

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

struct ForceAccelerationParam
{
double max_acceleration;
Expand Down Expand Up @@ -168,6 +174,7 @@ class MotionVelocitySmootherNode : 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 @@ -257,11 +264,16 @@ class MotionVelocitySmootherNode : 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
tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stop_watch_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@
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_ = this->add_on_set_parameters_callback(
Expand Down Expand Up @@ -205,6 +206,7 @@
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 @@ -334,6 +336,8 @@
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 MotionVelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory) const
Expand Down Expand Up @@ -504,6 +508,14 @@
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 @@ -589,6 +601,13 @@
// 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 @@ -1156,12 +1175,21 @@
}

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 1188 in planning/motion_velocity_smoother/src/motion_velocity_smoother_node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

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
Loading