/* 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); // send arming status arm_status_send(); } } 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 max_age_location_ms) { reason = "missing location message"; } else if (last_basic_id_ms == 0 || now_ms - last_basic_id_ms > max_age_other_ms) { reason = "missing basic_id message"; } else if (last_self_id_ms == 0 || now_ms - last_self_id_ms > max_age_other_ms) { reason = "missing self_id message"; } else if (last_operator_id_ms == 0 || now_ms - last_operator_id_ms > max_age_other_ms) { reason = "missing operator_id message"; } else if (last_system_ms == 0 || now_ms - last_system_ms > max_age_other_ms) { reason = "missing system message"; } else if (location.latitude == 0 && location.longitude == 0) { reason = "Bad location"; } else if (system.operator_latitude == 0 && system.operator_longitude == 0) { reason = "Bad operator location"; } else { status = MAV_ODID_GOOD_TO_ARM; } mavlink_msg_open_drone_id_arm_status_send( chan, status, reason); } /* return true when we have the base set of packets */ bool MAVLinkSerial::initialised(void) { const uint32_t required = PKT_LOCATION | PKT_BASIC_ID | PKT_SELF_ID | PKT_SYSTEM | PKT_OPERATOR_ID; return (packets_received_mask & required) == required; } bool MAVLinkSerial::system_valid(void) { uint32_t now_ms = millis(); uint32_t max_ms = 15000; if (last_system_ms == 0 || last_self_id_ms == 0 || last_basic_id_ms == 0 || last_operator_id_ms == 0) { return false; } return (now_ms - last_system_ms < max_ms && now_ms - last_self_id_ms < max_ms && now_ms - last_basic_id_ms < max_ms && now_ms - last_operator_id_ms < max_ms); } bool MAVLinkSerial::location_valid(void) { uint32_t now_ms = millis(); uint32_t max_ms = 2000; return last_location_ms != 0 && now_ms - last_location_ms < max_ms; }