|
| 1 | +#include "mfd_crossbow.h" |
| 2 | +#include "common/mavlink.h" |
| 3 | + |
| 4 | +MFDCrossbow::MFDCrossbow(HardwareSerial *port) : |
| 5 | + m_port(port), |
| 6 | + gpsLastSent(0), |
| 7 | + gpsLastUpdated(0), |
| 8 | + heading(0), |
| 9 | + lat(0.0), |
| 10 | + lon(0.0), |
| 11 | + alt(0.0), |
| 12 | + groundspeed(0.0), |
| 13 | + gps_sats(0), |
| 14 | + gps_alt(0), |
| 15 | + gps_hdop(100), |
| 16 | + fixType(3) |
| 17 | +{ |
| 18 | +} |
| 19 | + |
| 20 | +void |
| 21 | +MFDCrossbow::SendHeartbeat() |
| 22 | +{ |
| 23 | + // Initialize the required buffers |
| 24 | + mavlink_message_t msg; |
| 25 | + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; |
| 26 | + |
| 27 | + // Pack the message |
| 28 | + mavlink_msg_heartbeat_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_SYSTEM_TYPE, MAVLINK_AUTOPILOT_TYPE, MAVLINK_SYSTEM_MODE, MAVLINK_CUSTOM_MODE, MAVLINK_SYSTEM_STATE); |
| 29 | + |
| 30 | + // Copy the message to the send buffer |
| 31 | + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); |
| 32 | + |
| 33 | + // Send the message |
| 34 | + m_port->write(buf, len); |
| 35 | +} |
| 36 | + |
| 37 | +void |
| 38 | +MFDCrossbow::SendGpsRawInt() |
| 39 | +{ |
| 40 | + // Initialize the required buffers |
| 41 | + mavlink_message_t msg; |
| 42 | + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; |
| 43 | + |
| 44 | + const uint16_t eph = UINT16_MAX; |
| 45 | + const uint16_t epv = UINT16_MAX; |
| 46 | + const uint16_t cog = UINT16_MAX; |
| 47 | + const uint32_t alt_ellipsoid = 0; |
| 48 | + const uint32_t h_acc = 0; |
| 49 | + const uint32_t v_acc = 0; |
| 50 | + const uint32_t vel_acc = 0; |
| 51 | + const uint32_t hdg_acc = 0; |
| 52 | + |
| 53 | + // Pack the message |
| 54 | + mavlink_msg_gps_raw_int_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_UPTIME, fixType, lat, lon, alt, eph, epv, groundspeed, cog, gps_sats, alt_ellipsoid, h_acc, v_acc, vel_acc, hdg_acc, heading); |
| 55 | + |
| 56 | + // Copy the message to the send buffer |
| 57 | + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); |
| 58 | + |
| 59 | + // Send the message |
| 60 | + m_port->write(buf, len); |
| 61 | +} |
| 62 | + |
| 63 | +void |
| 64 | +MFDCrossbow::SendGlobalPositionInt() |
| 65 | +{ |
| 66 | + const int16_t velx = 0; |
| 67 | + const int16_t vely = 0; |
| 68 | + const int16_t velz = 0; |
| 69 | + |
| 70 | + // Initialize the required buffers |
| 71 | + mavlink_message_t msg; |
| 72 | + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; |
| 73 | + |
| 74 | + // Pack the message |
| 75 | + mavlink_msg_global_position_int_pack(MAVLINK_SYSTEM_ID, MAVLINK_COMPONENT_ID, &msg, MAVLINK_UPTIME, lat, lon, gps_alt, alt, velx, vely, velz, heading); |
| 76 | + |
| 77 | + // Copy the message to the send buffer |
| 78 | + uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); |
| 79 | + |
| 80 | + // Send the message |
| 81 | + m_port->write(buf, len); |
| 82 | +} |
| 83 | + |
| 84 | +void |
| 85 | +MFDCrossbow::SendGpsTelemetry(crsf_packet_gps_t *packet) |
| 86 | +{ |
| 87 | + int32_t rawLat = be32toh(packet->p.lat); // Convert to host byte order |
| 88 | + int32_t rawLon = be32toh(packet->p.lon); // Convert to host byte order |
| 89 | + lat = static_cast<double>(rawLat); |
| 90 | + lon = static_cast<double>(rawLon); |
| 91 | + |
| 92 | + // Convert from CRSF scales to mavlink scales |
| 93 | + groundspeed = be16toh(packet->p.speed) / 36.0 * 100.0; |
| 94 | + heading = be16toh(packet->p.heading); |
| 95 | + alt = (be16toh(packet->p.altitude) - 1000) * 1000.0; |
| 96 | + gps_alt = alt; |
| 97 | + gps_sats = packet->p.satcnt; |
| 98 | + |
| 99 | + // Send heartbeat and GPS mavlink messages to the tracker |
| 100 | + SendHeartbeat(); |
| 101 | + SendGpsRawInt(); |
| 102 | + SendGlobalPositionInt(); |
| 103 | + |
| 104 | + // Log the last time we received new GPS coords |
| 105 | + gpsLastUpdated = millis(); |
| 106 | +} |
| 107 | + |
| 108 | +void |
| 109 | +MFDCrossbow::Loop(uint32_t now) |
| 110 | +{ |
| 111 | + ModuleBase::Loop(now); |
| 112 | + |
| 113 | + // If the GPS data is <= 10 seconds old, keep spamming it out at 10hz |
| 114 | + bool gpsIsValid = (now < gpsLastUpdated + 10000) && gps_sats > 0; |
| 115 | + |
| 116 | + if (now > gpsLastSent + 100 && gpsIsValid) |
| 117 | + { |
| 118 | + SendHeartbeat(); |
| 119 | + SendGpsRawInt(); |
| 120 | + SendGlobalPositionInt(); |
| 121 | + |
| 122 | + gpsLastSent = now; |
| 123 | + } |
| 124 | +} |
0 commit comments