Copter: correct mav result for compass motor calibration on heli

This commit is contained in:
Peter Barker 2018-02-23 14:11:12 +11:00 committed by Francisco Ferreira
parent 234dcc1939
commit 9cffa13f7b
1 changed files with 1 additions and 1 deletions

View File

@ -9,7 +9,7 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan)
{
#if FRAME_CONFIG == HELI_FRAME
// compassmot not implemented for tradheli
return MAV_RESULT_TEMPORARILY_REJECTED;
return MAV_RESULT_UNSUPPORTED;
#else
int8_t comp_type; // throttle or current based compensation
Vector3f compass_base[COMPASS_MAX_INSTANCES]; // compass vector when throttle is zero