Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Guided mode handling to Mavlink telemetry #10424

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 18 additions & 2 deletions src/main/telemetry/mavlink.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
Loading