mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_FLYMAPLE: Console is now a thin wrapper around uartA, consistent with AVR
This commit is contained in:
parent
b02dbca9d4
commit
06478bde52
|
@ -14,6 +14,8 @@
|
||||||
*/
|
*/
|
||||||
/*
|
/*
|
||||||
Flymaple port by Mike McCauley
|
Flymaple port by Mike McCauley
|
||||||
|
This is just a thin wrapper around teh UART driver.
|
||||||
|
On Flymaple, the AP Console outputs to a Flymaple UART Serial port, not the SerialUSB port.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
@ -35,8 +37,9 @@ using namespace AP_HAL_FLYMAPLE_NS;
|
||||||
FLYMAPLEConsoleDriver::FLYMAPLEConsoleDriver(void* notused)
|
FLYMAPLEConsoleDriver::FLYMAPLEConsoleDriver(void* notused)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
void FLYMAPLEConsoleDriver::init(void* machtnichts)
|
void FLYMAPLEConsoleDriver::init(void* base_uart)
|
||||||
{
|
{
|
||||||
|
_base_uart = (AP_HAL::UARTDriver*) base_uart;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLEConsoleDriver::backend_open()
|
void FLYMAPLEConsoleDriver::backend_open()
|
||||||
|
@ -54,21 +57,19 @@ size_t FLYMAPLEConsoleDriver::backend_write(const uint8_t *data, size_t len) {
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t FLYMAPLEConsoleDriver::available() {
|
int16_t FLYMAPLEConsoleDriver::available() {
|
||||||
return SerialUSB.available();
|
return _base_uart->available();
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t FLYMAPLEConsoleDriver::txspace() {
|
int16_t FLYMAPLEConsoleDriver::txspace() {
|
||||||
// REVISIT mikem
|
return _base_uart->txspace();
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t FLYMAPLEConsoleDriver::read() {
|
int16_t FLYMAPLEConsoleDriver::read() {
|
||||||
return SerialUSB.read();
|
return _base_uart->read();
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t FLYMAPLEConsoleDriver::write(uint8_t c) {
|
size_t FLYMAPLEConsoleDriver::write(uint8_t c) {
|
||||||
SerialUSB.write(c);
|
return _base_uart->write(c);
|
||||||
return 1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -6,7 +6,7 @@
|
||||||
|
|
||||||
class AP_HAL_FLYMAPLE_NS::FLYMAPLEConsoleDriver : public AP_HAL::ConsoleDriver {
|
class AP_HAL_FLYMAPLE_NS::FLYMAPLEConsoleDriver : public AP_HAL::ConsoleDriver {
|
||||||
public:
|
public:
|
||||||
FLYMAPLEConsoleDriver(void* notused);
|
FLYMAPLEConsoleDriver(void* baseuartdriver);
|
||||||
void init(void* machtnichts);
|
void init(void* machtnichts);
|
||||||
void backend_open();
|
void backend_open();
|
||||||
void backend_close();
|
void backend_close();
|
||||||
|
@ -19,6 +19,7 @@ public:
|
||||||
|
|
||||||
size_t write(uint8_t c);
|
size_t write(uint8_t c);
|
||||||
private:
|
private:
|
||||||
|
AP_HAL::UARTDriver* _base_uart;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_FLYMAPLE_CONSOLE_H__
|
#endif // __AP_HAL_FLYMAPLE_CONSOLE_H__
|
||||||
|
|
|
@ -62,21 +62,31 @@ Resource usage
|
||||||
Resources on the Flymaple board have been allocated by the HAL:
|
Resources on the Flymaple board have been allocated by the HAL:
|
||||||
|
|
||||||
Pins
|
Pins
|
||||||
0 GPS Rx in
|
0 AP GPS on Flymaple Serial2 Rx in. This is where you connect the
|
||||||
|
GPS. 3.3V only, NOT 5V tolerant
|
||||||
|
1 AP GPS on Flymaple Serial2 Tx out. This is where you connect the GPS.
|
||||||
|
3.3V
|
||||||
6 Receiver PPM in
|
6 Receiver PPM in
|
||||||
7 GCS Rx in
|
7 Console and Mavlink on Flymaple Serial1 Rx in. Also on connector
|
||||||
8 GCS Tx out
|
"COM1". 5V tolerant.
|
||||||
15 3.3V board VCC analog in
|
8 Console and Mavlink on Flymaple Serial1 Tx out. Also on connector
|
||||||
16 Airspeed analog in (if available)
|
"COM1". 3.3V
|
||||||
19 Battery current analog in (if available)
|
15 3.3V board VCC analog in. Connect to 3.3V pin.
|
||||||
|
16 Airspeed analog in (if available). 3.3V, NOT 5V tolerant.
|
||||||
|
19 Battery current analog in (if available). 3.3V, NOT 5V tolerant.
|
||||||
20 Battery voltage analog in (on-board divider connected to board VIN)
|
20 Battery voltage analog in (on-board divider connected to board VIN)
|
||||||
|
29 Telemetry Tx to radio on Serial3 on connector labelled "GPS". 3.3V
|
||||||
|
30 Telemetry Rx from radio on Serial3 on connector labelled "GPS". 5V tolerant.
|
||||||
|
|
||||||
Timers
|
Timers
|
||||||
SysTick 100Hz normal timers
|
SysTick 1000Hz normal timers
|
||||||
1 RCInput
|
1 RCInput
|
||||||
2 Failsafe timer
|
2 1000Hz Failsafe timer
|
||||||
3,4 RCOut
|
3,4 RCOut
|
||||||
8 not used
|
8 not used by AP
|
||||||
|
|
||||||
|
The SerialUSB (USB connection) to Flymaple is not used by AP. It can be used for
|
||||||
|
debugging inside AP_HAL_FLYMAPLE, using SerialUSB.println().
|
||||||
|
|
||||||
Installation on Linux
|
Installation on Linux
|
||||||
|
|
||||||
|
|
|
@ -24,13 +24,13 @@
|
||||||
|
|
||||||
using namespace AP_HAL_FLYMAPLE_NS;
|
using namespace AP_HAL_FLYMAPLE_NS;
|
||||||
class HardwareSerial;
|
class HardwareSerial;
|
||||||
extern HardwareSerial Serial1;
|
extern HardwareSerial Serial1; // Serial1 is labelled "COM1" on Flymaple pins 7 and 8
|
||||||
extern HardwareSerial Serial2;
|
extern HardwareSerial Serial2; // Serial2 is Flymaple pins 0 and 1
|
||||||
extern HardwareSerial Serial3;
|
extern HardwareSerial Serial3; // Serial3 is labelled "GPS" on Flymaple pins 29 and 30
|
||||||
|
|
||||||
static FLYMAPLEUARTDriver uartADriver(&Serial1); // "COM1"
|
static FLYMAPLEUARTDriver uartADriver(&Serial1); // AP Console and highspeed mavlink
|
||||||
static FLYMAPLEUARTDriver uartBDriver(&Serial2);
|
static FLYMAPLEUARTDriver uartBDriver(&Serial2); // AP GPS connection
|
||||||
static FLYMAPLEUARTDriver uartCDriver(&Serial3); // "GPS"
|
static FLYMAPLEUARTDriver uartCDriver(&Serial3); // Optional AP telemetry radio
|
||||||
static FLYMAPLESemaphore i2cSemaphore;
|
static FLYMAPLESemaphore i2cSemaphore;
|
||||||
static FLYMAPLEI2CDriver i2cDriver(&i2cSemaphore);
|
static FLYMAPLEI2CDriver i2cDriver(&i2cSemaphore);
|
||||||
static FLYMAPLESPIDeviceManager spiDeviceManager;
|
static FLYMAPLESPIDeviceManager spiDeviceManager;
|
||||||
|
@ -66,7 +66,11 @@ void HAL_FLYMAPLE::init(int argc,char* const argv[]) const {
|
||||||
* up to the programmer to do this in the correct order.
|
* up to the programmer to do this in the correct order.
|
||||||
* Scheduler should likely come first. */
|
* Scheduler should likely come first. */
|
||||||
scheduler->init(NULL);
|
scheduler->init(NULL);
|
||||||
console->init(NULL);
|
|
||||||
|
/* uartA is the serial port used for the console, so lets make sure
|
||||||
|
* it is initialized at boot */
|
||||||
|
uartA->begin(115200);
|
||||||
|
console->init(uartA);
|
||||||
|
|
||||||
/* The AVR RCInput drivers take an AP_HAL_AVR::ISRRegistry*
|
/* The AVR RCInput drivers take an AP_HAL_AVR::ISRRegistry*
|
||||||
* as the init argument */
|
* as the init argument */
|
||||||
|
|
Loading…
Reference in New Issue