Browse Source

StandardModes: only enable for daily builds

QGC4.4
Beat Küng 2 years ago
parent
commit
c002ef6f70
  1. 4
      src/Vehicle/StandardModes.cc
  2. 4
      src/Vehicle/Vehicle.cc

4
src/Vehicle/StandardModes.cc

@ -114,6 +114,7 @@ void StandardModes::ensureUniqueModeNames() @@ -114,6 +114,7 @@ void StandardModes::ensureUniqueModeNames()
void StandardModes::request()
{
#ifdef DAILY_BUILD // Disable use of development/WIP MAVLink messages for release builds
if (_requestActive) {
// If we are in the middle of waiting for a request, wait for the response first
_wantReset = true;
@ -125,6 +126,9 @@ void StandardModes::request() @@ -125,6 +126,9 @@ void StandardModes::request()
qCDebug(StandardModesLog) << "Requesting available modes";
// Request one at a time. This could be improved by requesting all, but we can't use Vehicle::requestMessage for that
StandardModes::requestMode(1);
#else
emit requestCompleted();
#endif // DAILY_BUILD
}
void StandardModes::requestMode(int modeIndex)

4
src/Vehicle/Vehicle.cc

@ -765,7 +765,8 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes @@ -765,7 +765,8 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
}
}
break;
case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
#ifdef DAILY_BUILD // Disable use of development/WIP MAVLink messages for release builds
case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
{
// Avoid duplicate requests during initial connection setup
if (!_initialConnectStateMachine || !_initialConnectStateMachine->active()) {
@ -778,6 +779,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes @@ -778,6 +779,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_CURRENT_MODE:
_handleCurrentMode(message);
break;
#endif // DAILY_BUILD
// Following are ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)

Loading…
Cancel
Save