@ -3849,6 +3849,19 @@ int Vehicle::versionCompare(int major, int minor, int patch)
return _firmwarePlugin->versionCompare(this, major, minor, patch);
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::flashBootloader(void)
{
sendMavCommand(defaultComponentId(),
MAV_CMD_FLASH_BOOTLOADER,
true, // show error
0, 0, 0, 0, // param 1-4 not used
290876); // magic number
#endif
//-----------------------------------------------------------------------------
@ -756,6 +756,10 @@ public:
/// @param percent 0-no power, 100-full power
Q_INVOKABLE void motorTest(int motor, int percent);
Q_INVOKABLE void flashBootloader(void);
bool guidedModeSupported (void) const;
bool pauseVehicleSupported (void) const;
bool orbitModeSupported (void) const;