Rover: fix PID desired and achieved reporting

This commit is contained in:
Randy Mackay 2017-10-25 21:17:51 +09:00
parent ea70755f00
commit 2ef1e8e4c2

View File

@ -218,13 +218,12 @@ void Rover::send_rangefinder(mavlink_channel_t chan)
*/
void Rover::send_pid_tuning(mavlink_channel_t chan)
{
const Vector3f &gyro = ahrs.get_gyro();
const DataFlash_Class::PID_Info *pid_info;
if (g.gcs_pid_mask & 1) {
pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info();
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
pid_info->desired,
degrees(gyro.z),
degrees(pid_info->desired),
degrees(ahrs.get_yaw_rate_earth()),
pid_info->FF,
pid_info->P,
pid_info->I,
@ -235,9 +234,11 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
}
if (g.gcs_pid_mask & 2) {
pid_info = &g2.attitude_control.get_throttle_speed_pid().get_pid_info();
float speed = 0.0f;
g2.attitude_control.get_forward_speed(speed);
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
pid_info->desired,
0,
speed,
0,
pid_info->P,
pid_info->I,