Browse Source

Enable ROIModeCapability for ArduPilot vehicles

This enables two UI features when connected to an ArduPilot vehicle:

  1. click the map in the Fly View and send an "ROI at Location" command; and
  2. add an ROI as part of a Mission Plan.

Note that there is no way to determine if an ArduPilot build will accept
these commands. The commands will be accepted if the current connected
ArduPilot vehicle has both:

  1. the Mount driver included (i.e. compiled with HAL_MOUNT_ENABLED); and
  2. a Mount driver enabled (via the MNTn_TYPE parameter)

If ROIs are not supported, the ArduPilot vehicle will respond with a
MAV_RESULT_UNSUPPORTED command ack message.

Addresses #10640.
QGC4.4
Nick Exton 2 years ago committed by Philipp Borgers
parent
commit
99825d5279
  1. 2
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

2
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -77,7 +77,7 @@ AutoPilotPlugin* APMFirmwarePlugin::autopilotPlugin(Vehicle* vehicle) @@ -77,7 +77,7 @@ AutoPilotPlugin* APMFirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities capabilities)
{
uint32_t available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
uint32_t available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability | ROIModeCapability;
if (vehicle->multiRotor()) {
available |= TakeoffVehicleCapability;
} else if (vehicle->vtol()) {

Loading…
Cancel
Save