diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9f540b7fc56959c81724739fc555a40d91a64ea0..64eadc702907e632fde581f57e7a14219bdcdd21 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -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 + + //----------------------------------------------------------------------------- //----------------------------------------------------------------------------- diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index cba6240ea911692c2e6e05377215bd9268b7e120..530a4ed13ae9e1aae3959bdedf9967070bc271ba 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -756,6 +756,10 @@ public: /// @param percent 0-no power, 100-full power Q_INVOKABLE void motorTest(int motor, int percent); +#if !defined(NO_ARDUPILOT_DIALECT) + Q_INVOKABLE void flashBootloader(void); +#endif + bool guidedModeSupported (void) const; bool pauseVehicleSupported (void) const; bool orbitModeSupported (void) const;