GCS_MAVLink: remove PX4-specific code that disables overrides on reboot

This commit is contained in:
Peter Barker 2019-01-18 15:28:30 +11:00 committed by Andrew Tridgell
parent 06bb02fab7
commit 33baae80b1
2 changed files with 0 additions and 31 deletions

View File

@ -341,10 +341,8 @@ 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);
virtual bool should_disable_overrides_on_reboot() const { return true; }
virtual bool should_zero_rc_outputs_on_reboot() const { return false; }
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet);
void disable_overrides();
// reset a message interval via mavlink:
MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet);

View File

@ -28,12 +28,6 @@
#include "GCS.h"
#include <stdio.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#include <drivers/drv_pwm_output.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#endif
#if HAL_RCINPUT_WITH_AP_RADIO
#include <AP_Radio/AP_Radio.h>
@ -2407,25 +2401,6 @@ void GCS_MAVLINK::zero_rc_outputs()
SRV_Channels::push();
}
void GCS_MAVLINK::disable_overrides()
{
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
int px4io_fd = open("/dev/px4io", 0);
if (px4io_fd < 0) {
return;
}
// disable OVERRIDES so we don't run the mixer while
// rebooting
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_OK, 0) != 0) {
hal.console->printf("SET_OVERRIDE_OK failed\n");
}
if (ioctl(px4io_fd, PWM_SERVO_SET_OVERRIDE_IMMEDIATE, 0) != 0) {
hal.console->printf("SET_OVERRIDE_IMMEDIATE failed\n");
}
close(px4io_fd);
#endif
}
/*
handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command
@ -2441,10 +2416,6 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
return MAV_RESULT_UNSUPPORTED;
}
if (should_disable_overrides_on_reboot()) {
// disable overrides while rebooting
disable_overrides();
}
if (should_zero_rc_outputs_on_reboot()) {
zero_rc_outputs();
}