diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 14da530745..db6904cc51 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -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, diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 7d9632f421..9dc5919009 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -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()) {