@@ -62,6 +62,10 @@ PacmodInterface::PacmodInterface()
62
62
/* parameter for preventing gear chattering */
63
63
margin_time_for_gear_change_ = declare_parameter (" margin_time_for_gear_change" , 2.0 );
64
64
65
+ /* parameter for steering conversion */
66
+ enable_pub_steer_ = declare_parameter (" enable_pub_steer" , true );
67
+ convert_steer_command_ = declare_parameter (" convert_steer_command" , true );
68
+
65
69
/* initialize */
66
70
prev_steer_cmd_.header .stamp = this ->now ();
67
71
prev_steer_cmd_.command = 0.0 ;
@@ -321,7 +325,7 @@ void PacmodInterface::callbackPacmodRpt(
321
325
}
322
326
323
327
/* publish current status */
324
- {
328
+ if (enable_pub_steer_) {
325
329
autoware_vehicle_msgs::msg::SteeringReport steer_msg;
326
330
steer_msg.stamp = header.stamp ;
327
331
steer_msg.steering_tire_angle = current_steer;
@@ -330,11 +334,14 @@ void PacmodInterface::callbackPacmodRpt(
330
334
331
335
/* publish control status */
332
336
{
337
+ // NOTE:
338
+ // actuation status must be the same data format as the input data.
339
+ // raw_vehicle_cmd_converter converts from steering_wheel_angle to steering_tire_angle.
333
340
ActuationStatusStamped actuation_status;
334
341
actuation_status.header = header;
335
342
actuation_status.status .accel_status = accel_rpt_ptr_->output ;
336
343
actuation_status.status .brake_status = brake_rpt_ptr_->output ;
337
- actuation_status.status .steer_status = current_steer ;
344
+ actuation_status.status .steer_status = current_steer_wheel ;
338
345
actuation_status_pub_->publish (actuation_status);
339
346
}
340
347
@@ -396,11 +403,17 @@ void PacmodInterface::publishCommands()
396
403
const double current_steer_wheel = steer_wheel_rpt_ptr_->output ;
397
404
398
405
/* calculate desired steering wheel */
399
- double adaptive_gear_ratio = calculateVariableGearRatio (current_velocity, current_steer_wheel);
400
- double desired_steer_wheel =
401
- (control_cmd_ptr_->lateral .steering_tire_angle - steering_offset_) * adaptive_gear_ratio;
402
- desired_steer_wheel =
403
- std::min (std::max (desired_steer_wheel, -max_steering_wheel_), max_steering_wheel_);
406
+ const double adaptive_gear_ratio =
407
+ calculateVariableGearRatio (current_velocity, current_steer_wheel);
408
+ const double desired_steer_wheel = std::invoke ([&]() -> double {
409
+ double desired_steer_wheel{0.0 };
410
+ if (convert_steer_command_) {
411
+ (control_cmd_ptr_->lateral .steering_tire_angle - steering_offset_) * adaptive_gear_ratio;
412
+ } else {
413
+ desired_steer_wheel = actuation_cmd_ptr_->actuation .steer_cmd ;
414
+ }
415
+ return std::min (std::max (desired_steer_wheel, -max_steering_wheel_), max_steering_wheel_);
416
+ });
404
417
405
418
/* check clear flag */
406
419
bool clear_override = false ;
0 commit comments