├── .DS_Store ├── ESP32 MAVLink Simulator ├── .DS_Store ├── .gitignore ├── .travis.yml ├── include │ └── README ├── lib │ └── README ├── platformio.ini ├── src │ ├── commands.cpp │ ├── commands.h │ ├── input.cpp │ ├── input.h │ ├── main.cpp │ ├── settings.cpp │ └── settings.h └── test │ └── README ├── Libraries ├── .DS_Store └── MAVLink v2 C library_ID6412.zip └── README.md /.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/davwys/esp32-mavlink-sim/fc097be6333831220393641d6fc647c687f5e146/.DS_Store -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/davwys/esp32-mavlink-sim/fc097be6333831220393641d6fc647c687f5e146/ESP32 MAVLink Simulator/.DS_Store -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/.gitignore: -------------------------------------------------------------------------------- 1 | .pio 2 | .clang_complete 3 | .gcc-flags.json 4 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/.travis.yml: -------------------------------------------------------------------------------- 1 | # Continuous Integration (CI) is the practice, in software 2 | # engineering, of merging all developer working copies with a shared mainline 3 | # several times a day < https://docs.platformio.org/page/ci/index.html > 4 | # 5 | # Documentation: 6 | # 7 | # * Travis CI Embedded Builds with PlatformIO 8 | # < https://docs.travis-ci.com/user/integration/platformio/ > 9 | # 10 | # * PlatformIO integration with Travis CI 11 | # < https://docs.platformio.org/page/ci/travis.html > 12 | # 13 | # * User Guide for `platformio ci` command 14 | # < https://docs.platformio.org/page/userguide/cmd_ci.html > 15 | # 16 | # 17 | # Please choose one of the following templates (proposed below) and uncomment 18 | # it (remove "# " before each line) or use own configuration according to the 19 | # Travis CI documentation (see above). 20 | # 21 | 22 | 23 | # 24 | # Template #1: General project. Test it using existing `platformio.ini`. 25 | # 26 | 27 | # language: python 28 | # python: 29 | # - "2.7" 30 | # 31 | # sudo: false 32 | # cache: 33 | # directories: 34 | # - "~/.platformio" 35 | # 36 | # install: 37 | # - pip install -U platformio 38 | # - platformio update 39 | # 40 | # script: 41 | # - platformio run 42 | 43 | 44 | # 45 | # Template #2: The project is intended to be used as a library with examples. 46 | # 47 | 48 | # language: python 49 | # python: 50 | # - "2.7" 51 | # 52 | # sudo: false 53 | # cache: 54 | # directories: 55 | # - "~/.platformio" 56 | # 57 | # env: 58 | # - PLATFORMIO_CI_SRC=path/to/test/file.c 59 | # - PLATFORMIO_CI_SRC=examples/file.ino 60 | # - PLATFORMIO_CI_SRC=path/to/test/directory 61 | # 62 | # install: 63 | # - pip install -U platformio 64 | # - platformio update 65 | # 66 | # script: 67 | # - platformio ci --lib="." --board=ID_1 --board=ID_2 --board=ID_N 68 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/include/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for project header files. 3 | 4 | A header file is a file containing C declarations and macro definitions 5 | to be shared between several project source files. You request the use of a 6 | header file in your project source file (C, C++, etc) located in `src` folder 7 | by including it, with the C preprocessing directive `#include'. 8 | 9 | ```src/main.c 10 | 11 | #include "header.h" 12 | 13 | int main (void) 14 | { 15 | ... 16 | } 17 | ``` 18 | 19 | Including a header file produces the same results as copying the header file 20 | into each source file that needs it. Such copying would be time-consuming 21 | and error-prone. With a header file, the related declarations appear 22 | in only one place. If they need to be changed, they can be changed in one 23 | place, and programs that include the header file will automatically use the 24 | new version when next recompiled. The header file eliminates the labor of 25 | finding and changing all the copies as well as the risk that a failure to 26 | find one copy will result in inconsistencies within a program. 27 | 28 | In C, the usual convention is to give header files names that end with `.h'. 29 | It is most portable to use only letters, digits, dashes, and underscores in 30 | header file names, and at most one dot. 31 | 32 | Read more about using header files in official GCC documentation: 33 | 34 | * Include Syntax 35 | * Include Operation 36 | * Once-Only Headers 37 | * Computed Includes 38 | 39 | https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html 40 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/lib/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for project specific (private) libraries. 3 | PlatformIO will compile them to static libraries and link into executable file. 4 | 5 | The source code of each library should be placed in a an own separate directory 6 | ("lib/your_library_name/[here are source files]"). 7 | 8 | For example, see a structure of the following two libraries `Foo` and `Bar`: 9 | 10 | |--lib 11 | | | 12 | | |--Bar 13 | | | |--docs 14 | | | |--examples 15 | | | |--src 16 | | | |- Bar.c 17 | | | |- Bar.h 18 | | | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html 19 | | | 20 | | |--Foo 21 | | | |- Foo.c 22 | | | |- Foo.h 23 | | | 24 | | |- README --> THIS FILE 25 | | 26 | |- platformio.ini 27 | |--src 28 | |- main.c 29 | 30 | and a contents of `src/main.c`: 31 | ``` 32 | #include 33 | #include 34 | 35 | int main (void) 36 | { 37 | ... 38 | } 39 | 40 | ``` 41 | 42 | PlatformIO Library Dependency Finder will find automatically dependent 43 | libraries scanning project source files. 44 | 45 | More information about PlatformIO Library Dependency Finder 46 | - https://docs.platformio.org/page/librarymanager/ldf.html 47 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/platformio.ini: -------------------------------------------------------------------------------- 1 | ; PlatformIO Project Configuration File 2 | ; 3 | ; Build options: build flags, source filter 4 | ; Upload options: custom upload port, speed and extra flags 5 | ; Library options: dependencies, extra library storages 6 | ; Advanced options: extra scripting 7 | ; 8 | ; Please visit documentation for the other options and examples 9 | ; https://docs.platformio.org/page/projectconf.html 10 | 11 | 12 | [platformio] 13 | env_default = lolin_d32_pro 14 | 15 | [env:lolin_d32_pro] 16 | platform = espressif32 17 | board = lolin_d32_pro 18 | framework = arduino 19 | upload_port = /dev/tty.wchusbserial1420 20 | build_flags = -w ; Disable warnings, TODO do with -wno-error=reorder or similar 21 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/commands.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | #include 6 | #include 7 | /************************************************************ 8 | * @brief Sends a MAVLink heartbeat message, needed for the system to be recognized 9 | * @param Basic UAV parameters, as defined above 10 | * @return void 11 | *************************************************************/ 12 | 13 | void command_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) { 14 | 15 | // Initialize the required buffers 16 | mavlink_message_t msg; 17 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 18 | 19 | // Pack the message 20 | mavlink_msg_heartbeat_pack(system_id,component_id, &msg, system_type, autopilot_type, system_mode, custom_mode, system_state); 21 | 22 | // Copy the message to the send buffer 23 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 24 | 25 | // Send the message 26 | Serial.write(buf, len); 27 | 28 | // Send via Bluetooth (if enabled) 29 | if(bluetooth_enabled){ 30 | BTSerial.write(buf, len); 31 | } 32 | } 33 | 34 | /************************************************************ 35 | * @brief Sends a MAVLink parameter message, needed for the system to be recognized automatically in Mission Planner/QGroundcontrol 36 | * @param Basic UAV parameters, as defined above 37 | * @return void 38 | *************************************************************/ 39 | 40 | void command_parameters(int8_t system_id, uint8_t component_id) { 41 | 42 | // Initialize the required buffers 43 | mavlink_message_t msg; 44 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 45 | 46 | // Pack the message 47 | mavlink_msg_param_value_pack(system_id, component_id, &msg, "RC_SPEED", 50, 1, 1, 0); 48 | // Copy the message to the send buffer 49 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 50 | 51 | // Send the message 52 | Serial.write(buf, len); 53 | 54 | // Send via Bluetooth (if enabled) 55 | if(bluetooth_enabled){ 56 | BTSerial.write(buf, len); 57 | } 58 | } 59 | 60 | 61 | /************************************************************ 62 | * @brief Send some system data parameters (battery, etc) 63 | * @param 64 | * @return void 65 | *************************************************************/ 66 | 67 | void command_status(uint8_t system_id, uint8_t component_id, float battery_remaining, float voltage_battery, float current_battery) { 68 | 69 | // Initialize the required buffers 70 | mavlink_message_t msg; 71 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 72 | 73 | // Pack the message 74 | mavlink_msg_sys_status_pack(system_id, component_id, &msg, 32767, 32767, 32767, 500, voltage_battery * 1000.0, current_battery * 100.0, battery_remaining, 0, 0, 0, 0, 0, 0); 75 | 76 | // Copy the message to the send buffer 77 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 78 | 79 | // Send the message (.write sends as bytes) 80 | Serial.write(buf, len); 81 | 82 | // Send via Bluetooth (if enabled) 83 | if(bluetooth_enabled){ 84 | BTSerial.write(buf, len); 85 | } 86 | } 87 | 88 | /************************************************************ 89 | * @brief Sends Integer representation of location, only for ijnternal use (do not call directly) 90 | * @param lat: latitude, lon: longitude, alt: altitude, gps_alt: altitude above MSL, heading: heading 91 | * @return void 92 | *************************************************************/ 93 | 94 | void command_globalgps(int8_t system_id, int8_t component_id, int32_t upTime, float lat, float lon, float alt, float gps_alt, uint16_t heading) { 95 | 96 | int16_t velx = 0; //x speed 97 | int16_t vely = 0; //y speed 98 | int16_t velz = 0; //z speed 99 | 100 | 101 | // Initialize the required buffers 102 | mavlink_message_t msg; 103 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 104 | 105 | // Pack the message 106 | mavlink_msg_global_position_int_pack(system_id, component_id, &msg, upTime, lat * 10000000.0, lon * 10000000.0, gps_alt * 1000.0, alt * 1000.0, velx, vely, velz, heading); 107 | 108 | // Copy the message to the send buffer 109 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 110 | // Send the message (.write sends as bytes) 111 | Serial.write(buf, len); 112 | 113 | // Send via Bluetooth (if enabled) 114 | if(bluetooth_enabled){ 115 | BTSerial.write(buf, len); 116 | } 117 | } 118 | 119 | 120 | /************************************************************ 121 | * @brief Sends current geographical location (GPS position), altitude and heading 122 | * @param lat: latitude in degrees, lon: longitude in degrees, alt: altitude, heading: heading 123 | * @return void 124 | *************************************************************/ 125 | 126 | void command_gps(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) { 127 | 128 | // Initialize the required buffers 129 | mavlink_message_t msg; 130 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 131 | 132 | // Pack the message 133 | mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg, upTime, fixType, lat * 10000000.0, lon * 10000000.0, alt * 1000.0, gps_hdop * 100.0, 65535, groundspeed, 65535, gps_sats, 0, 0, 0, 0, 0); 134 | 135 | // Copy the message to the send buffer 136 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 137 | 138 | //Send globalgps command 139 | command_globalgps(system_id, component_id, upTime, lat, lon, alt, gps_alt, heading); 140 | 141 | // Send the message (.write sends as bytes) 142 | Serial.write(buf, len); 143 | 144 | // Send via Bluetooth (if enabled) 145 | if(bluetooth_enabled){ 146 | BTSerial.write(buf, len); 147 | } 148 | } 149 | 150 | /************************************************************ 151 | * @brief Send some core parameters such as speed to the MAVLink ground station HUD 152 | * @param 153 | * @return void 154 | *************************************************************/ 155 | 156 | void command_hud(int8_t system_id, int8_t component_id, float airspeed, float groundspeed, int16_t heading, float throttle, float alt, float climbrate) { 157 | 158 | // Initialize the required buffers 159 | mavlink_message_t msg; 160 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 161 | 162 | // Pack the message 163 | mavlink_msg_vfr_hud_pack(system_id, component_id, &msg, airspeed, groundspeed, heading, throttle, alt * 1000.0, climbrate); 164 | 165 | // Copy the message to the send buffer 166 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 167 | 168 | // Send the message (.write sends as bytes) 169 | Serial.write(buf, len); 170 | 171 | // Send via Bluetooth (if enabled) 172 | if(bluetooth_enabled){ 173 | BTSerial.write(buf, len); 174 | } 175 | } 176 | 177 | /************************************************************ 178 | * @brief Send attitude and heading data to the primary flight display (artificial horizon) 179 | * @param roll: roll in degrees, pitch: pitch in degrees, yaw: yaw in degrees, heading: heading in degrees 180 | * @return void 181 | *************************************************************/ 182 | 183 | void command_attitude(int8_t system_id, int8_t component_id, int32_t upTime, float roll, float pitch, float yaw) { 184 | 185 | //Radian -> degree conversion rate 186 | float radian = 57.2958; 187 | 188 | // Initialize the required buffers 189 | mavlink_message_t msg; 190 | uint8_t buf[MAVLINK_MAX_PACKET_LEN]; 191 | 192 | // Pack the message 193 | mavlink_msg_attitude_pack(system_id, component_id, &msg, upTime, roll/radian, pitch/radian, yaw/radian, 0, 0, 0); 194 | 195 | // Copy the message to the send buffer 196 | uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); 197 | // Send the message (.write sends as bytes) 198 | Serial.write(buf, len); 199 | 200 | // Send via Bluetooth (if enabled) 201 | if(bluetooth_enabled){ 202 | BTSerial.write(buf, len); 203 | } 204 | } 205 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/commands.h: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #ifndef COMMANDS_H 4 | #define COMMANDS_H 5 | 6 | 7 | // Send MAVLink heartbeat 8 | void command_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); 9 | 10 | // Send parameters 11 | void command_parameters(int8_t system_id, uint8_t component_id); 12 | 13 | // Send battery status 14 | void command_status(uint8_t system_id, uint8_t component_id, float battery_remaining, float voltage_battery, float current_battery); 15 | 16 | // Send GPS and altitude data 17 | void command_gps(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); 18 | 19 | // Send HUD data (speed, heading, climbrate etc.) 20 | void command_hud(int8_t system_id, int8_t component_id, float airspeed, float groundspeed, int16_t heading, float throttle, float alt, float climbrate); 21 | 22 | // Send attitude data to artificial horizon 23 | void command_attitude(int8_t system_id, int8_t component_id, int32_t upTime, float roll, float pitch, float yaw); 24 | 25 | #endif 26 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/input.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | // Parameter setup 5 | // These parameters may be entered manually, parsed from another protocol or simulated locally. 6 | // If your input protocol does not provide values for all of these, parameters may be left at their default values. 7 | // All parameters set here are passed onward through serial output in MAVLink format. 8 | 9 | //Basic UAV Parameters 10 | uint8_t system_id = 1; // MAVLink system ID. Leave at 0 unless you need a specific ID. 11 | uint8_t component_id = 0; // Should be left at 0. Set to 190 to simulate mission planner sending a command 12 | uint8_t system_type = 1; // UAV type. 0 = generic, 1 = fixed wing, 2 = quadcopter, 3 = helicopter 13 | uint8_t autopilot_type = 0; // Autopilot type. Usually set to 0 for generic autopilot with all capabilities 14 | uint8_t system_mode = 64; // Flight mode. 4 = auto mode, 8 = guided mode, 16 = stabilize mode, 64 = manual mode 15 | uint32_t custom_mode = 0; // Usually set to 0 16 | uint8_t system_state = 4; // 0 = unknown, 3 = standby, 4 = active 17 | uint32_t upTime = 0; // System uptime, usually set to 0 for cases where it doesn't matter 18 | 19 | // Flight parameters 20 | float roll = 0; // Roll angle in degrees 21 | float pitch = 0; // Pitch angle in degrees 22 | float yaw = 0; // Yaw angle in degrees 23 | int16_t heading = 0; // Geographical heading angle in degrees 24 | float lat = 47.379945; // GPS latitude in degrees (example: 47.123456) 25 | float lon = 8.539970; // GPS longitude in degrees 26 | float alt = 0.0; // Relative flight altitude in m 27 | float groundspeed = 0.0; // Groundspeed in m/s 28 | float airspeed = 0.0; // Airspeed in m/s 29 | float climbrate = 0.0; // Climb rate in m/s, currently not working 30 | float throttle = 0.0; // Throttle percentage 31 | 32 | // GPS parameters 33 | int16_t gps_sats = 0; // Number of visible GPS satellites 34 | int32_t gps_alt = 0.0; // GPS altitude (Altitude above MSL) 35 | float gps_hdop = 100.0; // GPS HDOP 36 | uint8_t fixType = 0; // GPS fix type. 0-1: no fix, 2: 2D fix, 3: 3D fix 37 | 38 | // Battery parameters 39 | float battery_remaining = 0.0; // Remaining battery percentage 40 | float voltage_battery = 0.0; // Battery voltage in V 41 | float current_battery = 0.0; // Battery current in A 42 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/input.h: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #ifndef INPUT_H 4 | #define INPUT_H 5 | 6 | //Basic UAV Parameters 7 | extern uint8_t system_id; 8 | extern uint8_t component_id; 9 | extern uint8_t system_type; 10 | extern uint8_t autopilot_type; 11 | extern uint8_t system_mode; 12 | extern uint32_t custom_mode; 13 | extern uint8_t system_state; 14 | extern uint32_t upTime; 15 | 16 | // Flight parameters 17 | extern float roll; 18 | extern float pitch; 19 | extern float yaw; 20 | extern int16_t heading; 21 | extern float lat; 22 | extern float lon; 23 | extern float alt; 24 | extern float groundspeed; 25 | extern float airspeed; 26 | extern float climbrate; //currently not working 27 | extern float throttle; 28 | 29 | // GPS parameters 30 | extern int16_t gps_sats; 31 | extern int32_t gps_alt; 32 | extern float gps_hdop; 33 | extern uint8_t fixType; 34 | 35 | // Battery parameters 36 | extern float battery_remaining; 37 | extern float voltage_battery; 38 | extern float current_battery; 39 | 40 | #endif 41 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/main.cpp: -------------------------------------------------------------------------------- 1 | // ESP32 MAVLink Simulation 2 | // 3 | // (c) 2020 David Wyss 4 | // 5 | // Base Arduino to MAVLink code from https://github.com/alaney/arduino-mavlink 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | // Serial Baud rate 15 | //Default: 57600 baud 16 | #define BAUD_RATE 57600 17 | 18 | // Telemetry message rate in Hz 19 | //Default: 10hz 20 | //Maximum: 40hz (depending on what additional processing is being done) 21 | #define TELEMETRY_HZ 10 22 | 23 | 24 | BluetoothSerial BTSerial; 25 | uint16_t wait = 1000/TELEMETRY_HZ; 26 | 27 | 28 | void setup() { 29 | // Enable serial output. 30 | Serial.begin(BAUD_RATE); 31 | // Enable bluetooth serial output 32 | BTSerial.begin("MAVLink"); 33 | } 34 | 35 | 36 | 37 | //Main loop: Send generated MAVLink data via USB (and bluetooth, if enabled) 38 | void loop() { 39 | 40 | // Send MAVLink heartbeat 41 | command_heartbeat(system_id, component_id, system_type, autopilot_type, system_mode, custom_mode, system_state); 42 | 43 | // Send parameters (needed for detection by some GCS software) 44 | command_parameters(system_id, component_id); 45 | 46 | //Send battery status 47 | command_status(system_id, component_id, battery_remaining, voltage_battery, current_battery); 48 | 49 | // Send GPS and altitude data 50 | command_gps(system_id, component_id, upTime, fixType, lat, lon, alt, gps_alt, heading, groundspeed, gps_hdop, gps_sats); 51 | 52 | // Send HUD data (speed, heading, climbrate etc.) 53 | command_hud(system_id, component_id, airspeed, groundspeed, heading, throttle, alt, climbrate); 54 | 55 | // Send attitude data to artificial horizon 56 | command_attitude(system_id, component_id, upTime, roll, pitch, yaw); 57 | 58 | //Delay: send messages at set rate 59 | delay(wait); 60 | } 61 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/settings.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include 4 | 5 | bool bluetooth_enabled = true; 6 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/src/settings.h: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | #ifndef SETTINGS_H 5 | #define SETTINGS_H 6 | 7 | extern bool bluetooth_enabled; 8 | extern BluetoothSerial BTSerial; 9 | 10 | #endif 11 | -------------------------------------------------------------------------------- /ESP32 MAVLink Simulator/test/README: -------------------------------------------------------------------------------- 1 | 2 | This directory is intended for PIO Unit Testing and project tests. 3 | 4 | Unit Testing is a software testing method by which individual units of 5 | source code, sets of one or more MCU program modules together with associated 6 | control data, usage procedures, and operating procedures, are tested to 7 | determine whether they are fit for use. Unit testing finds problems early 8 | in the development cycle. 9 | 10 | More information about PIO Unit Testing: 11 | - https://docs.platformio.org/page/plus/unit-testing.html 12 | -------------------------------------------------------------------------------- /Libraries/.DS_Store: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/davwys/esp32-mavlink-sim/fc097be6333831220393641d6fc647c687f5e146/Libraries/.DS_Store -------------------------------------------------------------------------------- /Libraries/MAVLink v2 C library_ID6412.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/davwys/esp32-mavlink-sim/fc097be6333831220393641d6fc647c687f5e146/Libraries/MAVLink v2 C library_ID6412.zip -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ESP32 MAVLink Simulator 2 | Simulate MAVLink commands for use with groundstation apps on an ESP32 3 | 4 | (ESP32 port of https://github.com/davwys/arduino-mavlink-sim) 5 | 6 | ## Introduction 7 | 8 | This is a general-purpose ESP32 program for simulating MAVLink telemetry data that can be used by common groundstation applications such as Mission Planner or APM Planner 2.0. 9 | The primary idea behind this is to serve as a base for using an ESP32 to convert other telemetry protocols (OpenTelemetry, BST, S.Port) to the very common MAVLink V2 format. This then allows the use of MAVLink-based groundstation applications with non-supported telemetry protocols. 10 | 11 | The program can also be used to simulate any type of MAVLink vehicle from an ESP32, as the parsed telemetry data can be sourced from any source connected to the ESP32 (for example, this would allow the use of Mission Planner to view telemetry from a simple ESP32-based rover). 12 | 13 | Note that the program does **NOT** convert any telemetry protocol or provide a data source - it only acts as an interface for converting raw input variables into MAVLink format. 14 | 15 | ## Installation & Testing 16 | 17 | Using Platformio, flash the program to your ESP32. You might need to change the settings in the platformio.ini file to suit the board you're using and choose the correct COM port. I used a Lolin D32 Pro board, but others should work as well. 18 | 19 | You will need the MAVLink library, provided in .zip format here or downloadable directly in Platformio. 20 | 21 | The ESP32 will then provide telemetry data through its USB port, as well as via Bluetooth. The default baud rate for both is set to 57600 and can be changed from the main.cpp file. To disable Bluetooth, change bluetooth_enabled to false in settings.cpp. 22 | 23 | Since the ESP32 offers more performance than an Arduino, the telemetry rate (hz) can be increased to up to 40hz. However, if you're doing additional processing (e.g. conversion of incoming data), I'd recommend leaving it at the default 10hz. 24 | 25 | From your groundstation application, simply choose the appropriate COM port, set baud rate to 57600 and hit "connect". 26 | 27 | ## Currently supported applications 28 | 29 | The following groundstation applications have been tested and are known to be working with this sketch: 30 | 31 | - [x] Mission Planner (Windows) 32 | - [x] APM Planner 2.0 (macOS/Windows) 33 | - [ ] QGroundcontrol (macOS/Windows) -> in progress 34 | 35 | ## Known issues 36 | 37 | - Climb rate and acceleration are currently unsupported 38 | 39 | 40 | If you find any further problems, feel free to open an issue! 41 | 42 | ## Future plans 43 | 44 | - Create separate versions for converting OpenTelemetry, BST and S.Port telemetry data into MAVLink format 45 | - Add support for QGroundcontrol 46 | 47 | 48 | #### (c) 2020 David Wyss 49 | --------------------------------------------------------------------------------