mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
GCS_MAVLink: tighten result of handle_preflight_reboot
This commit is contained in:
parent
161e2145cb
commit
e39e8359b6
@ -277,7 +277,7 @@ protected:
|
||||
void handle_common_message(mavlink_message_t *msg);
|
||||
void handle_set_gps_global_origin(const mavlink_message_t *msg);
|
||||
void handle_setup_signing(const mavlink_message_t *msg);
|
||||
uint8_t handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides);
|
||||
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides);
|
||||
MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet);
|
||||
virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet);
|
||||
|
||||
|
@ -1604,7 +1604,7 @@ void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position)
|
||||
motors. That can be dangerous when a preflight reboot is done with
|
||||
the pilot close to the aircraft and can also damage the aircraft
|
||||
*/
|
||||
uint8_t GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
|
||||
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, bool disable_overrides)
|
||||
{
|
||||
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
|
||||
if (disable_overrides) {
|
||||
|
Loading…
Reference in New Issue
Block a user