Rover: use AR_AttitudeControl::get_throttle_speed_pid_info

This commit is contained in:
Randy Mackay 2022-01-06 19:28:55 +09:00
parent 91d40b768c
commit 2c6e5d4b98
2 changed files with 2 additions and 2 deletions

View File

@ -206,7 +206,7 @@ void GCS_MAVLINK_Rover::send_pid_tuning()
// speed to throttle PID
if (g.gcs_pid_mask & 2) {
pid_info = &g2.attitude_control.get_throttle_speed_pid().get_pid_info();
pid_info = &g2.attitude_control.get_throttle_speed_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
pid_info->target,
pid_info->actual,

View File

@ -19,7 +19,7 @@ void Rover::Log_Write_Attitude()
// log steering rate controller
logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());
logger.Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid().get_pid_info());
logger.Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid_info());
// log pitch control for balance bots
if (is_balancebot()) {