mirror of https://github.com/ArduPilot/ardupilot
Tracker: remove usb-mux checking
This commit is contained in:
parent
87a3fcdd02
commit
b63b00f84e
|
@ -49,7 +49,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
|||
#endif
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50),
|
||||
SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100),
|
||||
SCHED_TASK(check_usb_mux, 10, 300),
|
||||
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
||||
SCHED_TASK(one_second_loop, 1, 3900),
|
||||
SCHED_TASK(compass_cal_update, 50, 100),
|
||||
|
|
|
@ -100,8 +100,6 @@ private:
|
|||
|
||||
uint32_t start_time_ms = 0;
|
||||
|
||||
bool usb_connected = false;
|
||||
|
||||
DataFlash_Class DataFlash;
|
||||
|
||||
AP_GPS gps;
|
||||
|
@ -236,7 +234,6 @@ private:
|
|||
void disarm_servos();
|
||||
void prepare_servos();
|
||||
void set_mode(enum ControlMode mode, mode_reason_t reason);
|
||||
void check_usb_mux(void);
|
||||
void update_vehicle_pos_estimate();
|
||||
void update_tracker_position();
|
||||
void update_bearing_and_distance();
|
||||
|
|
|
@ -49,11 +49,6 @@ void Tracker::init_tracker()
|
|||
barometer.set_log_baro_bit(MASK_LOG_IMU);
|
||||
barometer.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);
|
||||
|
||||
|
@ -219,17 +214,6 @@ void Tracker::set_mode(enum ControlMode mode, mode_reason_t reason)
|
|||
DataFlash.Log_Write_Mode(control_mode, reason);
|
||||
}
|
||||
|
||||
void Tracker::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;
|
||||
}
|
||||
|
||||
/*
|
||||
should we log a message type now?
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue