mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 22:48:29 -04:00
54c2c5f682
Instead of just doing a static cast to the desired class, use a method named "from". Pros: - When we have data shared on the parent class, the code is cleaner in child class when it needs to access this data. Almost all the data we use in AP_HAL benefits from this - There's a minimal type checking because now we are using a method that can only receive the type of the parent class
42 lines
896 B
C++
42 lines
896 B
C++
#ifndef __AP_HAL_LINUX_RPIOUARTDRIVER_H__
|
|
#define __AP_HAL_LINUX_RPIOUARTDRIVER_H__
|
|
|
|
#include "AP_HAL_Linux.h"
|
|
|
|
#include "UARTDriver.h"
|
|
|
|
|
|
class Linux::LinuxRPIOUARTDriver : public Linux::LinuxUARTDriver {
|
|
public:
|
|
LinuxRPIOUARTDriver();
|
|
|
|
static LinuxRPIOUARTDriver *from(AP_HAL::UARTDriver *uart) {
|
|
return static_cast<LinuxRPIOUARTDriver*>(uart);
|
|
}
|
|
|
|
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
|
void _timer_tick(void);
|
|
bool isExternal(void);
|
|
|
|
protected:
|
|
int _write_fd(const uint8_t *buf, uint16_t n);
|
|
int _read_fd(uint8_t *buf, uint16_t n);
|
|
|
|
private:
|
|
bool _in_timer;
|
|
|
|
bool sem_take_nonblocking();
|
|
void sem_give();
|
|
AP_HAL::SPIDeviceDriver *_spi;
|
|
AP_HAL::Semaphore *_spi_sem;
|
|
|
|
uint32_t _last_update_timestamp;
|
|
|
|
bool _external;
|
|
|
|
bool _need_set_baud;
|
|
uint32_t _baudrate;
|
|
};
|
|
|
|
#endif //__AP_HAL_LINUX_RPIOUARTDRIVER_H__
|