@@ -38,6 +38,7 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
38
38
: Node(" velocity_smoother" , node_options)
39
39
{
40
40
using std::placeholders::_1;
41
+ using std::placeholders::_2;
41
42
42
43
// set common params
43
44
const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils (*this ).getVehicleInfo ();
@@ -66,6 +67,13 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
66
67
sub_current_trajectory_ = create_subscription<Trajectory>(
67
68
" ~/input/trajectory" , 1 , std::bind (&VelocitySmootherNode::onCurrentTrajectory, this , _1));
68
69
70
+ srv_force_acceleration_ = create_service<SetBool>(
71
+ " ~/adjust_common_param" ,
72
+ std::bind (&MotionVelocitySmootherNode::onForceAcceleration, this , _1, _2));
73
+ srv_slow_driving_ = create_service<SetBool>(
74
+ " ~/slow_driving" , std::bind (&MotionVelocitySmootherNode::onSlowDriving, this , _1, _2));
75
+ force_acceleration_mode_ = false ;
76
+
69
77
// parameter update
70
78
set_param_res_ =
71
79
this ->add_on_set_parameters_callback (std::bind (&VelocitySmootherNode::onParameter, this , _1));
@@ -184,6 +192,14 @@ rcl_interfaces::msg::SetParametersResult VelocitySmootherNode::onParameter(
184
192
update_param (" ego_nearest_dist_threshold" , p.ego_nearest_dist_threshold );
185
193
update_param (" ego_nearest_yaw_threshold" , p.ego_nearest_yaw_threshold );
186
194
update_param_bool (" plan_from_ego_speed_on_manual_mode" , p.plan_from_ego_speed_on_manual_mode );
195
+
196
+ update_param (" force_acceleration.max_acc" , p.force_acceleration_param .max_acceleration );
197
+ update_param (" force_acceleration.max_jerk" , p.force_acceleration_param .max_jerk );
198
+ update_param (
199
+ " force_acceleration.max_lateral_acc" , p.force_acceleration_param .max_lateral_acceleration );
200
+ update_param (" force_acceleration.engage_velocity" , p.force_acceleration_param .engage_velocity );
201
+ update_param (
202
+ " force_acceleration.engage_acceleration" , p.force_acceleration_param .engage_acceleration );
187
203
}
188
204
189
205
{
@@ -303,6 +319,16 @@ void VelocitySmootherNode::initCommonParam()
303
319
304
320
p.plan_from_ego_speed_on_manual_mode =
305
321
declare_parameter<bool >(" plan_from_ego_speed_on_manual_mode" );
322
+
323
+ p.force_acceleration_param .max_acceleration =
324
+ declare_parameter<double >(" force_acceleration.max_acc" );
325
+ p.force_acceleration_param .max_jerk = declare_parameter<double >(" force_acceleration.max_jerk" );
326
+ p.force_acceleration_param .max_lateral_acceleration =
327
+ declare_parameter<double >(" force_acceleration.max_lateral_acc" );
328
+ p.force_acceleration_param .engage_velocity =
329
+ declare_parameter<double >(" force_acceleration.engage_velocity" );
330
+ p.force_acceleration_param .engage_acceleration =
331
+ declare_parameter<double >(" force_acceleration.engage_acceleration" );
306
332
}
307
333
308
334
void VelocitySmootherNode::publishTrajectory (const TrajectoryPoints & trajectory) const
@@ -1116,6 +1142,47 @@ TrajectoryPoint VelocitySmootherNode::calcProjectedTrajectoryPointFromEgo(
1116
1142
return calcProjectedTrajectoryPoint (trajectory, current_odometry_ptr_->pose .pose );
1117
1143
}
1118
1144
1145
+ void MotionVelocitySmootherNode::onForceAcceleration (
1146
+ const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response)
1147
+ {
1148
+ std::string message = " default" ;
1149
+
1150
+ if (request->data && !force_acceleration_mode_) {
1151
+ RCLCPP_INFO (get_logger (), " Force acceleration is activated" );
1152
+ smoother_->setMaxAccel (get_parameter (" force_acceleration.max_acc" ).as_double ());
1153
+ smoother_->setMaxJerk (get_parameter (" force_acceleration.max_jerk" ).as_double ());
1154
+ smoother_->setMaxLatAccel (get_parameter (" force_acceleration.max_lateral_acc" ).as_double ());
1155
+ node_param_.engage_velocity = get_parameter (" force_acceleration.engage_velocity" ).as_double ();
1156
+ node_param_.engage_acceleration =
1157
+ get_parameter (" force_acceleration.engage_acceleration" ).as_double ();
1158
+
1159
+ force_acceleration_mode_ = true ;
1160
+ message = " Trigger force acceleration" ;
1161
+ } else if (!request->data && force_acceleration_mode_) {
1162
+ RCLCPP_INFO (get_logger (), " Force acceleration is deactivated" );
1163
+ smoother_->setMaxAccel (get_parameter (" normal.max_acc" ).as_double ());
1164
+ smoother_->setMaxJerk (get_parameter (" normal.max_jerk" ).as_double ());
1165
+ smoother_->setMaxLatAccel (get_parameter (" max_lateral_accel" ).as_double ());
1166
+
1167
+ node_param_.engage_velocity = get_parameter (" engage_velocity" ).as_double ();
1168
+ node_param_.engage_acceleration = get_parameter (" engage_acceleration" ).as_double ();
1169
+
1170
+ force_acceleration_mode_ = false ;
1171
+ message = " Trigger normal acceleration" ;
1172
+ }
1173
+
1174
+ response->success = true ;
1175
+ }
1176
+
1177
+ void MotionVelocitySmootherNode::onSlowDriving (
1178
+ const std::shared_ptr<SetBool::Request> request, std::shared_ptr<SetBool::Response> response)
1179
+ {
1180
+ const std::string message = request->data ? " Slow driving" : " Default" ;
1181
+
1182
+ response->success = true ;
1183
+ response->message = message;
1184
+ }
1185
+
1119
1186
} // namespace autoware::velocity_smoother
1120
1187
1121
1188
#include " rclcpp_components/register_node_macro.hpp"
0 commit comments