@@ -68,8 +68,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
68
68
" ~/input/trajectory" , 1 , std::bind (&VelocitySmootherNode::onCurrentTrajectory, this , _1));
69
69
70
70
srv_force_acceleration_ = create_service<SetBool>(
71
- " ~/adjust_common_param" ,
72
- std::bind (&VelocitySmootherNode::onForceAcceleration, this , _1, _2));
71
+ " ~/adjust_common_param" , std::bind (&VelocitySmootherNode::onForceAcceleration, this , _1, _2));
73
72
srv_slow_driving_ = create_service<SetBool>(
74
73
" ~/slow_driving" , std::bind (&VelocitySmootherNode::onSlowDriving, this , _1, _2));
75
74
force_acceleration_mode_ = false ;
@@ -1201,7 +1200,7 @@ void VelocitySmootherNode::onSlowDriving(
1201
1200
if (request->data && force_slow_driving_mode_ == ForceSlowDrivingType::DEACTIVATED) {
1202
1201
force_slow_driving_mode_ = ForceSlowDrivingType::READY;
1203
1202
1204
- message = " Activated force slow drving " ;
1203
+ message = " Activated force slow driving " ;
1205
1204
} else if (!request->data ) {
1206
1205
force_slow_driving_mode_ = ForceSlowDrivingType::DEACTIVATED;
1207
1206
message = " Deactivated force slow driving" ;
0 commit comments