mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: fixed USB connected on AUAV-X2
this is the 2nd attempt at a fix for the usb_connected status on AUAV-X2
This commit is contained in:
parent
69bfeaf58e
commit
1b61f6f636
|
@ -245,10 +245,11 @@ bool PX4GPIO::usb_connected(void)
|
|||
struct stat st;
|
||||
/*
|
||||
we use a combination of voltage on the USB connector and the
|
||||
existance of the /dev/ttyACM0 character device. This copes with
|
||||
open of the /dev/ttyACM0 character device. This copes with
|
||||
systems where the VBUS may go high even with no USB connected
|
||||
(such as AUAV-X2)
|
||||
*/
|
||||
return stm32_gpioread(GPIO_OTGFS_VBUS) && stat("/dev/ttyACM0", &st) == 0;
|
||||
return stm32_gpioread(GPIO_OTGFS_VBUS) && _usb_connected;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -46,11 +46,15 @@ public:
|
|||
/* return true if USB cable is connected */
|
||||
bool usb_connected(void);
|
||||
|
||||
// used by UART code to avoid a hw bug in the AUAV-X2
|
||||
void set_usb_connected(void) { _usb_connected = true; }
|
||||
|
||||
private:
|
||||
int _led_fd;
|
||||
int _tone_alarm_fd;
|
||||
int _gpio_fmu_fd;
|
||||
int _gpio_io_fd;
|
||||
bool _usb_connected = false;
|
||||
};
|
||||
|
||||
class PX4::PX4DigitalSource : public AP_HAL::DigitalSource {
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
#include <drivers/drv_hrt.h>
|
||||
#include <assert.h>
|
||||
#include "../AP_HAL/utility/RingBuffer.h"
|
||||
#include "GPIO.h"
|
||||
|
||||
using namespace PX4;
|
||||
|
||||
|
@ -146,6 +147,9 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||
|
||||
if (_writebuf_size != 0 && _readbuf_size != 0 && _fd != -1) {
|
||||
if (!_initialised) {
|
||||
if (strcmp(_devpath, "/dev/ttyACM0") == 0) {
|
||||
((PX4GPIO *)hal.gpio)->set_usb_connected();
|
||||
}
|
||||
::printf("initialised %s OK %u %u\n", _devpath,
|
||||
(unsigned)_writebuf_size, (unsigned)_readbuf_size);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue