20 #define DEVOM_SYNC_BYTE 0xAA 23 #define AP_SERIALMANAGER_DEVO_TELEM_BAUD 38400 24 #define AP_SERIALMANAGER_DEVO_BUFSIZE_RX 0 25 #define AP_SERIALMANAGER_DEVO_BUFSIZE_TX 32 57 int32_t deg = (int32_t)ddm;
58 float mm = (ddm - deg) * 60.0
f;
60 mm = ((float)deg * 100.0
f + mm) /100.0;
62 if ((mm < -180.0
f) || (mm > 180.0f)) {
75 #define DEVO_SPEED_FACTOR 0.0194384f 80 if (
_port ==
nullptr) {
114 for (uint8_t i =
sizeof(
devoPacket)-1; i !=0; i--) {
AP_HAL::UARTDriver * _port
static AP_SerialManager serial_manager
void init(const AP_SerialManager &serial_manager)
virtual void begin(uint32_t baud)=0
virtual bool get_position(struct Location &loc) const =0
uint32_t gpsDdToDmsFormat(float ddm)
#define DEVO_SPEED_FACTOR
#define AP_SERIALMANAGER_DEVO_TELEM_BAUD
int32_t lat
param 3 - Latitude * 10**7
float ground_speed(uint8_t instance) const
virtual size_t write(uint8_t)=0
virtual void set_flow_control(enum flow_control flow_control_setting)
AP_DEVO_Telem(const AP_AHRS &ahrs)
AP_BattMonitor & battery()
#define AP_SERIALMANAGER_DEVO_BUFSIZE_RX
int32_t lng
param 4 - Longitude * 10**7
virtual void register_io_process(AP_HAL::MemberProc)=0
uint8_t header
0xAA for a valid packet
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void send_frames(uint8_t control_mode)
virtual void get_relative_position_D_home(float &posD) const =0
#define AP_SERIALMANAGER_DEVO_BUFSIZE_TX
AP_HAL::Scheduler * scheduler
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const