Copter: remove DigitalReadFast

With APHal all reads are fast
This commit is contained in:
Randy Mackay 2013-05-20 11:29:34 +09:00
parent 21f3534a93
commit 885ce7db03
2 changed files with 2 additions and 7 deletions

View File

@ -30,11 +30,6 @@ void digitalWrite(uint8_t pin, uint8_t out)
hal.gpio->write(pin,out);
}
uint8_t digitalReadFast(uint8_t pin)
{
return hal.gpio->read(pin);
}
uint8_t digitalRead(uint8_t pin)
{
return hal.gpio->read(pin);

View File

@ -82,7 +82,7 @@ static void init_ardupilot()
// USB_MUX_PIN
pinMode(USB_MUX_PIN, INPUT);
ap_system.usb_connected = !digitalReadFast(USB_MUX_PIN);
ap_system.usb_connected = !digitalRead(USB_MUX_PIN);
if (!ap_system.usb_connected) {
// USB is not connected, this means UART0 may be a Xbee, with
// its darned bricking problem. We can't write to it for at
@ -534,7 +534,7 @@ static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
#if USB_MUX_PIN > 0
static void check_usb_mux(void)
{
bool usb_check = !digitalReadFast(USB_MUX_PIN);
bool usb_check = !digitalRead(USB_MUX_PIN);
if (usb_check == ap_system.usb_connected) {
return;
}