diff --git a/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp b/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp index 688041c..804b576 100644 --- a/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp +++ b/pacmod_interface/src/pacmod_interface/pacmod_interface.cpp @@ -408,8 +408,10 @@ void PacmodInterface::publishCommands() const double desired_steer_wheel = std::invoke([&]() -> double { double desired_steer_wheel{0.0}; if (convert_steer_command_) { - desired_steer_wheel = - (control_cmd_ptr_->lateral.steering_tire_angle - steering_offset_) * adaptive_gear_ratio; + // NOTE: + // It is assumed that steer_cmd is send as actuation_cmd without being converted from + // raw_vehicle_cmd_converter. + desired_steer_wheel = (actuation.steer_cmd - steering_offset_) * adaptive_gear_ratio; } else { desired_steer_wheel = actuation_cmd_ptr_->actuation.steer_cmd; }