/* mavlink class for handling OpenDroneID messages */ #include #include "mavlink.h" #define SERIAL_BAUD 115200 static HardwareSerial *serial_ports[MAVLINK_COMM_NUM_BUFFERS]; #include mavlink_system_t mavlink_system = {2,1}; #define dev_printf(fmt, args ...) do {Serial.printf(fmt, ## args); } while(0) /* send a buffer out a MAVLink channel */ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len) { if (chan >= MAVLINK_COMM_NUM_BUFFERS || serial_ports[uint8_t(chan)] == nullptr) { return; } auto &serial = *serial_ports[uint8_t(chan)]; serial.write(buf, len); } /* abstraction for MAVLink on a serial port */ MAVLinkSerial::MAVLinkSerial(HardwareSerial &_serial, mavlink_channel_t _chan) : serial(_serial), chan(_chan) { serial_ports[uint8_t(_chan - MAVLINK_COMM_0)] = &serial; } void MAVLinkSerial::init(void) { } void MAVLinkSerial::update(void) { update_send(); update_receive(); } void MAVLinkSerial::update_send(void) { uint32_t now_ms = millis(); if (now_ms - last_hb_ms >= 1000) { last_hb_ms = now_ms; mavlink_msg_heartbeat_send( chan, MAV_TYPE_ODID, MAV_AUTOPILOT_ARDUPILOTMEGA, 0, 0, 0); } } void MAVLinkSerial::update_receive(void) { // receive new packets mavlink_message_t msg; mavlink_status_t status; uint32_t now_ms = millis(); status.packet_rx_drop_count = 0; const uint16_t nbytes = serial.available(); for (uint16_t i=0; i