Browse Source

APM: added support for MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN

this allows for remote reboot of APM
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
cb88681914
  1. 1
      ArduPlane/ArduPlane.pde
  2. 10
      ArduPlane/GCS_Mavlink.pde
  3. 14
      ArduPlane/system.pde

1
ArduPlane/ArduPlane.pde

@ -21,6 +21,7 @@ @@ -21,6 +21,7 @@
#include <avr/io.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <math.h>
// Libraries

10
ArduPlane/GCS_Mavlink.pde

@ -1042,7 +1042,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1042,7 +1042,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_command_long_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
uint8_t result;
uint8_t result = MAV_RESULT_UNSUPPORTED;
// do command
send_text(SEVERITY_LOW,PSTR("command received: "));
@ -1110,8 +1110,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1110,8 +1110,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (packet.param1 == 1) {
reboot_apm();
result = MAV_RESULT_ACCEPTED;
}
break;
default:
result = MAV_RESULT_UNSUPPORTED;
break;
}

14
ArduPlane/system.pde

@ -570,3 +570,17 @@ uint16_t board_voltage(void) @@ -570,3 +570,17 @@ uint16_t board_voltage(void)
return vcc.read_vcc();
}
/*
force a software reset of the APM
*/
static void reboot_apm(void)
{
Serial.println_P(PSTR("REBOOTING"));
delay(100);
// see http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1250663814/
// for the method
cli();
wdt_enable(WDTO_15MS);
while (1);
}

Loading…
Cancel
Save