mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: removed Console driver
This commit is contained in:
parent
b30f652cec
commit
7cab8cb3bb
|
@ -3,7 +3,6 @@
|
|||
#define __AP_HAL_PX4_NAMESPACE_H__
|
||||
|
||||
namespace PX4 {
|
||||
class PX4ConsoleDriver;
|
||||
class PX4Scheduler;
|
||||
class PX4UARTDriver;
|
||||
class PX4Storage;
|
||||
|
|
|
@ -1,53 +0,0 @@
|
|||
#include <AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include <stdarg.h>
|
||||
#include "Console.h"
|
||||
#include "UARTDriver.h"
|
||||
#include <stdio.h>
|
||||
|
||||
using namespace PX4;
|
||||
|
||||
PX4ConsoleDriver::PX4ConsoleDriver() {}
|
||||
|
||||
void PX4ConsoleDriver::init(void* uart)
|
||||
{
|
||||
_uart = (PX4UARTDriver *)uart;
|
||||
}
|
||||
|
||||
void PX4ConsoleDriver::backend_open()
|
||||
{}
|
||||
|
||||
void PX4ConsoleDriver::backend_close()
|
||||
{}
|
||||
|
||||
size_t PX4ConsoleDriver::backend_read(uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t PX4ConsoleDriver::backend_write(const uint8_t *data, size_t len) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
int16_t PX4ConsoleDriver::available() {
|
||||
return _uart->available();
|
||||
}
|
||||
|
||||
int16_t PX4ConsoleDriver::txspace() {
|
||||
return _uart->txspace();
|
||||
}
|
||||
|
||||
int16_t PX4ConsoleDriver::read() {
|
||||
return _uart->read();
|
||||
}
|
||||
|
||||
size_t PX4ConsoleDriver::write(uint8_t c) {
|
||||
return _uart->write(c);
|
||||
}
|
||||
|
||||
size_t PX4ConsoleDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
return _uart->write(buffer, size);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,28 +0,0 @@
|
|||
|
||||
#ifndef __AP_HAL_PX4_CONSOLE_H__
|
||||
#define __AP_HAL_PX4_CONSOLE_H__
|
||||
|
||||
#include <AP_HAL_PX4.h>
|
||||
#include <AP_HAL_PX4_Namespace.h>
|
||||
|
||||
class PX4::PX4ConsoleDriver : public AP_HAL::ConsoleDriver {
|
||||
public:
|
||||
PX4ConsoleDriver();
|
||||
void init(void* machtnichts);
|
||||
void backend_open();
|
||||
void backend_close();
|
||||
size_t backend_read(uint8_t *data, size_t len);
|
||||
size_t backend_write(const uint8_t *data, size_t len);
|
||||
|
||||
int16_t available();
|
||||
int16_t txspace();
|
||||
int16_t read();
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
private:
|
||||
PX4UARTDriver *_uart;
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_PX4_CONSOLE_H__
|
|
@ -7,7 +7,6 @@
|
|||
#include <AP_HAL_PX4.h>
|
||||
#include "AP_HAL_PX4_Namespace.h"
|
||||
#include "HAL_PX4_Class.h"
|
||||
#include "Console.h"
|
||||
#include "Scheduler.h"
|
||||
#include "UARTDriver.h"
|
||||
#include "Storage.h"
|
||||
|
@ -36,7 +35,6 @@ static Empty::EmptyI2CDriver i2cDriver(&i2cSemaphore);
|
|||
static Empty::EmptySPIDeviceManager spiDeviceManager;
|
||||
//static Empty::EmptyGPIO gpioDriver;
|
||||
|
||||
static PX4ConsoleDriver consoleDriver;
|
||||
static PX4Scheduler schedulerInstance;
|
||||
static PX4Storage storageDriver;
|
||||
static PX4RCInput rcinDriver;
|
||||
|
@ -63,7 +61,7 @@ HAL_PX4::HAL_PX4() :
|
|||
&spiDeviceManager, /* spi */
|
||||
&analogIn, /* analogin */
|
||||
&storageDriver, /* storage */
|
||||
&consoleDriver, /* console */
|
||||
&uartADriver, /* console */
|
||||
&gpioDriver, /* gpio */
|
||||
&rcinDriver, /* rcinput */
|
||||
&rcoutDriver, /* rcoutput */
|
||||
|
@ -114,7 +112,6 @@ static int main_loop(int argc, char **argv)
|
|||
hal.uartA->begin(115200);
|
||||
hal.uartB->begin(38400);
|
||||
hal.uartC->begin(57600);
|
||||
hal.console->init((void*) hal.uartA);
|
||||
hal.scheduler->init(NULL);
|
||||
hal.rcin->init(NULL);
|
||||
hal.rcout->init(NULL);
|
||||
|
|
Loading…
Reference in New Issue