Sub: Remove unused ap.usb_connected flag

This commit is contained in:
Jacob Walser 2017-04-14 19:11:13 -04:00
parent c093e1c37e
commit 8c6fa6f651
4 changed files with 0 additions and 21 deletions

View File

@ -382,8 +382,6 @@ void Sub::one_hz_loop()
// update assigned functions and enable auxiliary servos
SRV_Channels::enable_aux_servos();
check_usb_mux();
// update position controller alt limits
update_poscon_alt_max();

View File

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

View File

@ -228,7 +228,6 @@ private:
struct {
uint8_t pre_arm_check : 1; // true if all pre-arm checks (rc, accel calibration, gps lock) have been performed
uint8_t logging_started : 1; // true if dataflash logging has started
uint8_t usb_connected : 1; // true if APM is powered from USB connection
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
uint8_t motor_test : 1; // true if we are currently performing the motors test
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
@ -669,7 +668,6 @@ private:
bool position_ok();
bool ekf_position_ok();
bool optflow_position_ok();
void check_usb_mux(void);
bool should_log(uint32_t mask);
void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...);
bool start_command(const AP_Mission::Mission_Command& cmd);

View File

@ -55,11 +55,6 @@ void Sub::init_ardupilot()
// hal.scheduler->delay.
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
// we start by assuming USB connected, as we initialed the serial
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
ap.usb_connected = true;
check_usb_mux();
// setup telem slots with serial ports
for (uint8_t i = 0; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
gcs_chan[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
@ -284,17 +279,6 @@ bool Sub::optflow_position_ok()
#endif
}
void Sub::check_usb_mux(void)
{
bool usb_check = hal.gpio->usb_connected();
if (usb_check == ap.usb_connected) {
return;
}
// the user has switched to/from the telemetry port
ap.usb_connected = usb_check;
}
/*
should we log a message type now?
*/