Skip to content

Commit

Permalink
fix spelling mistake
Browse files Browse the repository at this point in the history
Signed-off-by: Go Sakayori <[email protected]>
  • Loading branch information
go-sakayori committed Aug 7, 2024
1 parent e3c1699 commit def5cad
Showing 1 changed file with 2 additions and 3 deletions.
5 changes: 2 additions & 3 deletions planning/autoware_velocity_smoother/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
"~/input/trajectory", 1, std::bind(&VelocitySmootherNode::onCurrentTrajectory, this, _1));

srv_force_acceleration_ = create_service<SetBool>(
"~/adjust_common_param",
std::bind(&VelocitySmootherNode::onForceAcceleration, this, _1, _2));
"~/adjust_common_param", std::bind(&VelocitySmootherNode::onForceAcceleration, this, _1, _2));
srv_slow_driving_ = create_service<SetBool>(
"~/slow_driving", std::bind(&VelocitySmootherNode::onSlowDriving, this, _1, _2));
force_acceleration_mode_ = false;
Expand Down Expand Up @@ -1201,7 +1200,7 @@ void VelocitySmootherNode::onSlowDriving(
if (request->data && force_slow_driving_mode_ == ForceSlowDrivingType::DEACTIVATED) {
force_slow_driving_mode_ = ForceSlowDrivingType::READY;

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

0 comments on commit def5cad

Please sign in to comment.