mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: handle MAV_CMD_FLASH_BOOTLOADER
This commit is contained in:
parent
a81b3c8a7c
commit
4a8614fbbd
|
@ -339,6 +339,7 @@ protected:
|
||||||
virtual uint32_t telem_delay() const = 0;
|
virtual uint32_t telem_delay() const = 0;
|
||||||
|
|
||||||
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
|
MAV_RESULT handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet);
|
||||||
|
MAV_RESULT handle_command_flash_bootloader(const mavlink_command_long_t &packet);
|
||||||
|
|
||||||
// generally this should not be overridden; Plane overrides it to ensure
|
// generally this should not be overridden; Plane overrides it to ensure
|
||||||
// failsafe isn't triggered during calibation
|
// failsafe isn't triggered during calibation
|
||||||
|
|
|
@ -2456,6 +2456,20 @@ void GCS_MAVLINK::send_simstate() const
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_long_t &packet)
|
||||||
|
{
|
||||||
|
if (int(packet.param5) != 290876) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "Magic not set");
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!hal.util->flash_bootloader()) {
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
|
||||||
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
|
||||||
{
|
{
|
||||||
Compass *compass = get_compass();
|
Compass *compass = get_compass();
|
||||||
|
@ -2680,6 +2694,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_message(mavlink_command_long_t &pack
|
||||||
result = handle_command_preflight_calibration(packet);
|
result = handle_command_preflight_calibration(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_FLASH_BOOTLOADER:
|
||||||
|
result = handle_command_flash_bootloader(packet);
|
||||||
|
break;
|
||||||
|
|
||||||
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
|
case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
|
||||||
result = handle_command_preflight_set_sensor_offsets(packet);
|
result = handle_command_preflight_set_sensor_offsets(packet);
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue