Skip to content
Open
Show file tree
Hide file tree
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
7 changes: 4 additions & 3 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -4218,14 +4218,15 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
break;
#endif

#ifdef USE_BARO
#if defined(USE_BARO) || defined(USE_GPS)
case MSP2_INAV_SET_ALT_TARGET:
if (dataSize != (sizeof(int32_t) + sizeof(uint8_t))) {
*ret = MSP_RESULT_ERROR;
break;
}

if (navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)sbufReadU8(src), (int32_t)sbufReadU32(src))) {
uint8_t setAltDatum = (geoAltitudeDatumFlag_e)sbufReadU8(src);
int32_t setNewAlt = sbufReadU32(src);
if (navigationSetAltitudeTargetWithDatum(setAltDatum, setNewAlt)) {
Comment thread
sensei-hacker marked this conversation as resolved.
*ret = MSP_RESULT_ACK;
break;
}
Expand Down
9 changes: 8 additions & 1 deletion src/main/navigation/navigation.c
Original file line number Diff line number Diff line change
Expand Up @@ -5204,7 +5204,14 @@ bool navigationIsControllingAltitude(void) {
bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm)
{
const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) {
if (!(stateFlags & NAV_CTL_ALT) ||
(stateFlags & NAV_CTL_LAND) ||
navigationIsExecutingAnEmergencyLanding() ||
posControl.flags.estAltStatus == EST_NONE ||
(stateFlags & NAV_MIXERAT) ||
FLIGHT_MODE(NAV_FW_AUTOLAND) ||
FLIGHT_MODE(NAV_SEND_TO) ||
((stateFlags & NAV_AUTO_RTH) && posControl.navState != NAV_STATE_RTH_HEAD_HOME)) {
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/telemetry/mavlink.c
Original file line number Diff line number Diff line change
Expand Up @@ -1215,7 +1215,7 @@ static bool handleIncoming_COMMAND_INT(void)
mavlinkSendMessage();
}
} else {
#ifdef USE_BARO
#if defined(USE_BARO) || defined(USE_GPS)
if (msg.command == MAV_CMD_DO_CHANGE_ALTITUDE) {
const float altitudeMeters = msg.param1;
const uint8_t frame = (uint8_t)msg.frame;
Expand Down
Loading