mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Send ESC telemetry over mavlink while doing compassmot
compassmot can be used to bypass all PID control loops (this avoids forwarding IMU noise to the motors) while stress-testing the ESCs+motors. So that temperatures can be monitored in real-time during those long tests, send ESC telemetry as well.
This commit is contained in:
parent
26e867ebf2
commit
e7c82e86d2
@ -224,6 +224,10 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||
motor_compensation[0].x,
|
||||
motor_compensation[0].y,
|
||||
motor_compensation[0].z);
|
||||
#if HAL_WITH_ESC_TELEM
|
||||
// send ESC telemetry to monitor ESC and motor temperatures
|
||||
AP::esc_telem().send_esc_telemetry_mavlink(gcs_chan.get_chan());
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user