Skip to content

Commit 1816618

Browse files
committed
use steer angle of actuation cmd even when not convert_steer_command
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent df52c6a commit 1816618

File tree

1 file changed

+4
-2
lines changed

1 file changed

+4
-2
lines changed

pacmod_interface/src/pacmod_interface/pacmod_interface.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -408,8 +408,10 @@ void PacmodInterface::publishCommands()
408408
const double desired_steer_wheel = std::invoke([&]() -> double {
409409
double desired_steer_wheel{0.0};
410410
if (convert_steer_command_) {
411-
desired_steer_wheel =
412-
(control_cmd_ptr_->lateral.steering_tire_angle - steering_offset_) * adaptive_gear_ratio;
411+
// NOTE:
412+
// It is assumed that steer_cmd is send as actuation_cmd without being converted from
413+
// raw_vehicle_cmd_converter.
414+
desired_steer_wheel = (actuation.steer_cmd - steering_offset_) * adaptive_gear_ratio;
413415
} else {
414416
desired_steer_wheel = actuation_cmd_ptr_->actuation.steer_cmd;
415417
}

0 commit comments

Comments
 (0)