Rover: report left and right wheel control PID

This commit is contained in:
Randy Mackay 2018-08-08 13:15:07 +09:00
parent e0fa829665
commit 5aa1286344
2 changed files with 32 additions and 2 deletions

View File

@ -227,6 +227,36 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
return;
}
}
// left wheel rate control pid
if (g.gcs_pid_mask & 8) {
pid_info = &g2.wheel_rate_control.get_pid(0).get_pid_info();
mavlink_msg_pid_tuning_send(chan, 7,
pid_info->desired,
pid_info->actual,
pid_info->FF,
pid_info->P,
pid_info->I,
pid_info->D);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
// right wheel rate control pid
if (g.gcs_pid_mask & 16) {
pid_info = &g2.wheel_rate_control.get_pid(1).get_pid_info();
mavlink_msg_pid_tuning_send(chan, 8,
pid_info->desired,
pid_info->actual,
pid_info->FF,
pid_info->P,
pid_info->I,
pid_info->D);
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
return;
}
}
}
void Rover::send_fence_status(mavlink_channel_t chan)

View File

@ -64,8 +64,8 @@ const AP_Param::Info Rover::var_info[] = {
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
// @Values: 0:None,1:Steering,2:Throttle,4:Pitch
// @Bitmask: 0:Steering,1:Throttle,2:Pitch
// @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel
// @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
// @Param: MAG_ENABLE