diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 4e8d54535a3..4acc20cc44d 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -196,7 +196,15 @@ static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode) case FLM_HORIZON: return COPTER_MODE_STABILIZE; case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE; case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD; - case FLM_POSITION_HOLD: return COPTER_MODE_POSHOLD; + case FLM_POSITION_HOLD: + { + if (IS_RC_MODE_ACTIVE(BOXGCSNAV)) { + return COPTER_MODE_GUIDED; + } + else { + return COPTER_MODE_POSHOLD; + } + } case FLM_RTH: return COPTER_MODE_RTL; case FLM_MISSION: return COPTER_MODE_AUTO; case FLM_LAUNCH: return COPTER_MODE_THROW; @@ -226,7 +234,15 @@ static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode) case FLM_HORIZON: return PLANE_MODE_STABILIZE; case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE; case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B; - case FLM_POSITION_HOLD: return PLANE_MODE_LOITER; + case FLM_POSITION_HOLD: + { + if (IS_RC_MODE_ACTIVE(BOXGCSNAV)) { + return PLANE_MODE_GUIDED; + } + else { + return PLANE_MODE_LOITER; + } + } case FLM_RTH: return PLANE_MODE_RTL; case FLM_MISSION: return PLANE_MODE_AUTO; case FLM_CRUISE: return PLANE_MODE_CRUISE;