mirror of https://github.com/ArduPilot/ardupilot
Rover: remove usb-mux checking
Nobody ever uses the result from this
This commit is contained in:
parent
eb1ae22bb1
commit
87a3fcdd02
|
@ -66,7 +66,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
SCHED_TASK(read_aux_switch, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200),
|
||||
SCHED_TASK(check_usb_mux, 3, 200),
|
||||
#if MOUNT == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),
|
||||
#endif
|
||||
|
|
|
@ -1222,7 +1222,6 @@ void Rover::mavlink_delay_cb()
|
|||
last_5s = tnow;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
||||
}
|
||||
check_usb_mux();
|
||||
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
|
|
@ -231,9 +231,6 @@ private:
|
|||
// true if initialisation has completed
|
||||
bool initialised;
|
||||
|
||||
// if USB is connected
|
||||
bool usb_connected;
|
||||
|
||||
// This is the state of the flight control system
|
||||
// There are multiple states defined such as MANUAL, AUTO, ...
|
||||
Mode *control_mode;
|
||||
|
@ -525,7 +522,6 @@ private:
|
|||
bool set_mode(Mode &new_mode, mode_reason_t reason);
|
||||
bool mavlink_set_mode(uint8_t mode);
|
||||
void startup_INS_ground(void);
|
||||
void check_usb_mux(void);
|
||||
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
||||
void notify_mode(const Mode *new_mode);
|
||||
uint8_t check_digital_pin(uint8_t pin);
|
||||
|
|
|
@ -70,11 +70,6 @@ void Rover::init_ardupilot()
|
|||
// init baro before we start the GCS, so that the CLI baro test works
|
||||
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);
|
||||
|
||||
|
@ -288,17 +283,6 @@ void Rover::startup_INS_ground(void)
|
|||
ahrs.reset();
|
||||
}
|
||||
|
||||
void Rover::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;
|
||||
}
|
||||
|
||||
// update notify with mode change
|
||||
void Rover::notify_mode(const Mode *mode)
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue