Skip to content

Commit

Permalink
mavlink out
Browse files Browse the repository at this point in the history
  • Loading branch information
wvarty committed Jul 12, 2024
1 parent ef5add0 commit abf04f8
Show file tree
Hide file tree
Showing 6 changed files with 212 additions and 23 deletions.
1 change: 1 addition & 0 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@ extra_configs =
targets/rapidfire.ini
targets/rx5808.ini
targets/skyzone.ini
targets/mfd_crossbow.ini
38 changes: 16 additions & 22 deletions src/Vrx_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@
#include "orqa.h"
#elif defined(AAT_BACKPACK)
#include "module_aat.h"
#elif defined(CROSSBOW_BACKPACK)
#include "mfd_crossbow.h"
#endif

/////////// DEFINES ///////////
Expand Down Expand Up @@ -121,6 +123,8 @@ uint8_t cachedLen = 0;
Orqa vrxModule;
#elif defined(AAT_BACKPACK)
AatModule vrxModule(Serial);
#elif defined(CROSSBOW_BACKPACK)
MFDCrossbow vrxModule(&Serial);
#endif

/////////// FUNCTION DEFS ///////////
Expand Down Expand Up @@ -251,28 +255,16 @@ void ProcessMSPPacket(mspPacket_t *packet)
DBGLN("CRSF_TLM packet too short")
break;
}
// switch (packet->payload[2]) {
// case CRSF_FRAMETYPE_GPS:
// vrxModule.SendGpsTelemetry((crsf_packet_gps_t *)packet->payload);
// break;
// case CRSF_FRAMETYPE_BATTERY_SENSOR:
// vrxModule.SendBatteryTelemetry(packet->payload);
// break;
// case CRSF_FRAMETYPE_LINK_STATISTICS:
// vrxModule.SendLinkTelemetry(packet->payload);
// break;
// }
DBGLN("*** DUMP CRSF TO UART ***");
for(int i = 0; i < packet->payloadSize; i++)
{
DBGV("%x,", packet->payload[i]); // Debug prints
}
DBGLN(""); // Extra line for serial output readability
Serial.write(packet->payload, packet->payloadSize);
if (packet->payload[2] == CRSF_FRAMETYPE_GPS)
{
memcpy(cachedGPS, packet->payload, packet->payloadSize);
cachedLen = packet->payloadSize;
switch (packet->payload[2]) {
case CRSF_FRAMETYPE_GPS:
vrxModule.SendGpsTelemetry((crsf_packet_gps_t *)packet->payload);
break;
case CRSF_FRAMETYPE_BATTERY_SENSOR:
vrxModule.SendBatteryTelemetry(packet->payload);
break;
case CRSF_FRAMETYPE_LINK_STATISTICS:
vrxModule.SendLinkTelemetry(packet->payload);
break;
}
break;
default:
Expand Down Expand Up @@ -343,6 +335,7 @@ void SetSoftMACAddress()

void RequestVTXPacket()
{
#if !defined(AAT_BACKPACK) and !defined(CROSSBOW_BACKPACK)
mspPacket_t packet;
packet.reset();
packet.makeCommand();
Expand All @@ -351,6 +344,7 @@ void RequestVTXPacket()

blinkLED();
sendMSPViaEspnow(&packet);
#endif
}

void sendMSPViaEspnow(mspPacket_t *packet)
Expand Down
136 changes: 136 additions & 0 deletions src/mfd_crossbow.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
#include "mfd_crossbow.h"
#include "common/mavlink.h"

//Basic UAV Parameters
uint8_t system_id = 1; // MAVLink system ID. Leave at 0 unless you need a specific ID.
uint8_t component_id = 1; // Should be left at 0. Set to 190 to simulate mission planner sending a command
uint8_t system_type = 1; // UAV type. 0 = generic, 1 = fixed wing, 2 = quadcopter, 3 = helicopter
uint8_t autopilot_type = 3; // Autopilot type. Usually set to 0 for generic autopilot with all capabilities
uint8_t system_mode = 64; // Flight mode. 4 = auto mode, 8 = guided mode, 16 = stabilize mode, 64 = manual mode
uint32_t custom_mode = 0; // Usually set to 0
uint8_t system_state = 4; // 0 = unknown, 3 = standby, 4 = active
uint32_t upTime = 0; // System uptime, usually set to 0 for cases where it doesn't matter

// Flight parameters
float roll = 0; // Roll angle in degrees
float pitch = 0; // Pitch angle in degrees
float yaw = 0; // Yaw angle in degrees
int16_t heading = 0; // Geographical heading angle in degrees
float lat = 0.0; // GPS latitude in degrees (example: 47.123456)
float lon = 0.0; // GPS longitude in degrees
float alt = 0.0; // Relative flight altitude in m
float lat_temp = 0.0; //Temp values for GPS coords
float lon_temp = 0.0;
float groundspeed = 0.0; // Groundspeed in m/s
float airspeed = 0.0; // Airspeed in m/s
float climbrate = 0.0; // Climb rate in m/s, currently not working
float throttle = 0.0; // Throttle percentage

// GPS parameters
int16_t gps_sats = 0; // Number of visible GPS satellites
int32_t gps_alt = 0.0; // GPS altitude (Altitude above MSL)
float gps_hdop = 100.0; // GPS HDOP
uint8_t fixType = 0; // GPS fix type. 0-1: no fix, 2: 2D fix, 3: 3D fix

// Battery parameters
float battery_remaining = 0.0; // Remaining battery percentage
float voltage_battery = 0.0; // Battery voltage in V
float current_battery = 0.0; // Battery current in A


void
MFDCrossbow::send_heartbeat(uint8_t system_id, uint8_t component_id, uint8_t system_type, uint8_t autopilot_type, uint8_t system_mode, uint32_t custom_mode, uint8_t system_state)
{
// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// Pack the message
mavlink_msg_heartbeat_pack(system_id,component_id, &msg, system_type, autopilot_type, system_mode, custom_mode, system_state);

// Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

// Send the message
m_port->write(buf, len);
}

void
MFDCrossbow::send_gps_raw_int(int8_t system_id, int8_t component_id, int32_t upTime, int8_t fixType, float lat, float lon, float alt, float gps_alt, int16_t heading, float groundspeed, float gps_hdop, int16_t gps_sats)
{
// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

uint16_t eph = UINT16_MAX;
uint16_t epv = UINT16_MAX;
uint16_t vel = groundspeed;
uint16_t cog = UINT16_MAX;
uint8_t satellites_visible = gps_sats;
uint32_t alt_ellipsoid = 0;
uint32_t h_acc = 0;
uint32_t v_acc = 0;
uint32_t vel_acc = 0;
uint32_t hdg_acc = 0;
uint16_t yaw = heading;

// Pack the message
mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg, upTime, fixType, lat, lon, alt, eph, epv, vel, cog, satellites_visible, alt_ellipsoid, h_acc, v_acc, vel_acc, hdg_acc, yaw);

// // Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

m_port->write(buf, len);
}

void
MFDCrossbow::send_global_position_int(int8_t system_id, int8_t component_id, int32_t upTime, float lat, float lon, float alt, float gps_alt, uint16_t heading)
{
int16_t velx = 0; //x speed
int16_t vely = 0; //y speed
int16_t velz = 0; //z speed

// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// Pack the message
mavlink_msg_global_position_int_pack(system_id, component_id, &msg, upTime, lat, lon, gps_alt, alt, velx, vely, velz, heading);

// Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

// Send the message (.write sends as bytes)
m_port->write(buf, len);
}

void
MFDCrossbow::SendGpsTelemetry(crsf_packet_gps_t *packet)
{
int32_t rawLat = be32toh(packet->p.lat); // Convert to host byte order
int32_t rawLon = be32toh(packet->p.lon); // Convert to host byte order
lat = static_cast<double>(rawLat);
lon = static_cast<double>(rawLon);

groundspeed = be16toh(packet->p.speed) / 36.0 * 100.0;
heading = be16toh(packet->p.heading);
alt = (be16toh(packet->p.altitude) - 1000) * 1000.0;
gps_sats = packet->p.satcnt;

// m_port->println("GPS lat: ");
// m_port->println(lat);
// m_port->println("GPS lon: ");
// m_port->println(lon);
// m_port->println("GPS speed: ");
// m_port->println(groundspeed);
// m_port->println("GPS heading: ");
// m_port->println(heading);
// m_port->println("GPS altitude: ");
// m_port->println(alt);
// m_port->println("GPS satellites: ");
// m_port->println(gps_sats);

send_heartbeat(system_id, component_id, system_type, autopilot_type, system_mode, custom_mode, system_state);
send_gps_raw_int(system_id, component_id, upTime, fixType, lat, lon, alt, gps_alt, heading, groundspeed, gps_hdop, gps_sats);
send_global_position_int(system_id, component_id, upTime, lat, lon, alt, gps_alt, heading);
}
20 changes: 20 additions & 0 deletions src/mfd_crossbow.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
#pragma once

#include "module_base.h"
#include "msptypes.h"

#define VRX_UART_BAUD 115200

class MFDCrossbow : public ModuleBase
{
public:
MFDCrossbow(HardwareSerial *port) : m_port(port) {};

void send_heartbeat(uint8_t system_id, uint8_t component_id, uint8_t system_type, uint8_t autopilot_type, uint8_t system_mode, uint32_t custom_mode, uint8_t system_state);
void send_gps_raw_int(int8_t system_id, int8_t component_id, int32_t upTime, int8_t fixType, float lat, float lon, float alt, float gps_alt, int16_t heading, float groundspeed, float gps_hdop, int16_t gps_sats);
void send_global_position_int(int8_t system_id, int8_t component_id, int32_t upTime, float lat, float lon, float alt, float gps_alt, uint16_t heading);
void SendGpsTelemetry(crsf_packet_gps_t *packet);

private:
HardwareSerial *m_port;
};
3 changes: 2 additions & 1 deletion targets/common.ini
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ lib_deps =
ottowinter/ESPAsyncWebServer-esphome @ 3.0.0
esphome/AsyncTCP-esphome @ 2.0.1 # use specific version - an update to this library breaks the build
bblanchon/ArduinoJson @ 6.19.4
https://github.com/mavlink/c_library_v2.git#e54a8d2e8cf7985e689ad1c8c8f37dc0800ea87b

[common_env_data]
build_src_filter = +<*> -<.git/> -<svn/> -<example/> -<examples/> -<test/> -<tests/> -<*.py> -<*test*.*>
Expand Down Expand Up @@ -90,7 +91,7 @@ lib_ignore = STM32UPDATE
build_flags =
${common_env_data.build_flags}
-D TARGET_VRX_BACKPACK
-D STEADYVIEW_BACKPACK
-D CROSSBOW_BACKPACK
build_src_filter = ${common_env_data.build_src_filter} -<Tx_main.cpp> -<rapidfire.*> -<rx5808.*> -<fusion.*> -<hdzero.*> -<skyzone_msp.*> -<orqa.*> -<Timer_main.cpp>
lib_ignore = STM32UPDATE

Expand Down
37 changes: 37 additions & 0 deletions targets/mfd_crossbow.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
# ********************************
# MFD Crossbow tracker backpack
# ********************************

[env:MFD_Crossbow_ESP8285_Backpack_via_UART]
extends = env_common_esp12e
build_flags =
${common_env_data.build_flags}
${env_common_esp12e.build_flags}
-D TARGET_VRX_BACKPACK
-D CROSSBOW_BACKPACK
-D PIN_BUTTON=0
-D PIN_LED=16
lib_ignore = STM32UPDATE
lib_deps =
${env.lib_deps}
build_src_filter = ${common_env_data.build_src_filter} -<Tx_main.cpp> -<rapidfire.*> -<rx5808.*> -<steadyview.*> -<Timer_main.cpp>

[env:MFD_Crossbow_ESP8285_Backpack_via_WIFI]
extends = env:MFD_Crossbow_ESP8285_Backpack_via_UART

[env:MFD_Crossbow_ESP32_Backpack_via_UART]
extends = env_common_esp32
build_flags =
${common_env_data.build_flags}
${env_common_esp32.build_flags}
-D TARGET_VRX_BACKPACK
-D CROSSBOW_BACKPACK
-D PIN_BUTTON=0
-D PIN_LED=16
lib_ignore = STM32UPDATE
lib_deps =
${env.lib_deps}
build_src_filter = ${common_env_data.build_src_filter} -<Tx_main.cpp> -<rapidfire.*> -<rx5808.*> -<steadyview.*> -<Timer_main.cpp>

[env:MFD_Crossbow_ESP32_Backpack_via_WIFI]
extends = env:MFD_Crossbow_ESP32_Backpack_via_UART

0 comments on commit abf04f8

Please sign in to comment.