mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: correct mav result for compass motor calibration on heli
This commit is contained in:
parent
234dcc1939
commit
9cffa13f7b
@ -9,7 +9,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
|
|||||||
{
|
{
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// compassmot not implemented for tradheli
|
// compassmot not implemented for tradheli
|
||||||
return MAV_RESULT_TEMPORARILY_REJECTED;
|
return MAV_RESULT_UNSUPPORTED;
|
||||||
#else
|
#else
|
||||||
int8_t comp_type; // throttle or current based compensation
|
int8_t comp_type; // throttle or current based compensation
|
||||||
Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero
|
Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero
|
||||||
|
Loading…
Reference in New Issue
Block a user