Plane: allow battery failsafe with usb connected

some people connect USB to allow connections from a companion
computer. The arming check is sufficient to prevent unwanted battery
failsafes when bench testing
This commit is contained in:
Andrew Tridgell 2017-02-07 16:49:33 +11:00
parent 27e52695fe
commit 954905e0eb
5 changed files with 1 additions and 25 deletions

View File

@ -52,7 +52,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(gcs_update, 50, 500),
SCHED_TASK(gcs_data_stream_send, 50, 500),
SCHED_TASK(update_events, 50, 150),
SCHED_TASK(check_usb_mux, 10, 100),
SCHED_TASK(read_battery, 10, 300),
SCHED_TASK(compass_accumulate, 50, 200),
SCHED_TASK(barometer_accumulate, 50, 150),

View File

@ -2163,7 +2163,6 @@ void Plane::mavlink_delay_cb()
last_5s = tnow;
gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM");
}
check_usb_mux();
in_mavlink_delay = false;
}

View File

@ -284,9 +284,6 @@ private:
// RSSI
AP_RSSI rssi;
// remember if USB is connected, so we can adjust baud rate
bool usb_connected;
// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
enum FlightMode control_mode = INITIALISING;
@ -982,7 +979,6 @@ private:
void startup_INS_ground(void);
void update_notify();
void resetPerfData(void);
void check_usb_mux(void);
void print_comma(void);
bool should_log(uint32_t mask);
int8_t throttle_percentage(void);

View File

@ -118,8 +118,7 @@ void Plane::read_battery(void)
battery.read();
compass.set_current(battery.current_amps());
if (!usb_connected &&
hal.util->get_soft_armed() &&
if (hal.util->get_soft_armed() &&
battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah)) {
low_battery_event();
}

View File

@ -165,11 +165,6 @@ void Plane::init_ardupilot()
rpm_sensor.init();
// we start by assuming USB connected, as we initialed the serial
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
usb_connected = true;
check_usb_mux();
// setup telem slots with serial ports
gcs().setup_uarts(serial_manager);
@ -680,18 +675,6 @@ void Plane::resetPerfData(void)
}
void Plane::check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
if (usb_check == usb_connected) {
return;
}
// the user has switched to/from the telemetry port
usb_connected = usb_check;
}
void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{
switch (mode) {