Skip to content

rotary-auav-ui/ESP32-MAVLink

 
 

Repository files navigation

ESP32 MAVLink

ESP32 MAVLink is a modified version of the MAVLink C Library v2 that is compatible with the ESP32 platform. This library is meant to be used with the Cigritous Project and tested with the ESP32 DevKitC. Connect the ESP32 to the drone using a telemtry via TX2 and RX2 pins. Meanwhile, the telemetry on the drone should be connected to TELEM1 port. The ESP32 will be used to send commands to the drone and receive telemetry data from the drone. The ESP32 will act as the Ground Control Station (GCS) for the drone.

This library was build for the AUTO/MISSION mode of the drone. The drone will be able to takeoff, fly to a waypoint, and land. The drone will also be able to receive commands from the ESP32 to change the flight mode. The ESP32 will be able to receive telemetry data from the drone such as the drone's position, attitude, and battery level.

Requirements

This is the only hardware this was tested. Other similar ESP32 boards should work as well.

The link above redirects to the Holybro telemtry radio. This is the only telemetry radio this was tested. Other similar telemetry radios should work as well.

Installation

If you are using the Cigritous Project then you can skip this step because the library is already included in the project. If you are using this library in your own project, you can install it by cloning this repository into your project's libraries folder.

Usage

Include the mavlink_commands header file.

#include <mavlink_commands.hpp>

Create a MAVLink object or choose any name you like. Recommended to be in the global scope in the form of a shared pointer. For debugging purposes, serial 0 communication can be started so the output can be seen in the serial monitor. Example :

#include <mavlink_commands.hpp>

std::shared_ptr<MAVLink> mavlink;

void setup(){
    Serial.begin(115200);
    mavlink = std::make_shared<MAVLink>(57600, 16, 17);
}

The MAVLink constructor takes 3 parameters. The first parameter is the baud rate of the serial communication. The second and third parameters are the TX and RX pins of the ESP32. The default baud rate is 57600. The default TX and RX pins are 16 and 17 respectively.

Add waypoint using the add_waypoint function. The add_waypoint function takes 3 parameters. The first parameter is the latitude of the waypoint. The second parameter is the longitude of the waypoint. The third parameter is the altitude of the waypoint. The altitude is in meters. Example :

mavlink->add_waypoint(14.599512, 120.984222, 10);

Or it is overloaded to use the default fly altitude. The default fly altitude can be set using the set_fly_alt function. The set_fly_alt function takes 1 parameter. The parameter is the altitude in meters. Example :

mavlink->set_fly_alt(10);

Then, you can use the add_waypoint function without the altitude parameter. Example :

mavlink->add_waypoint(14.599512, 120.984222);

Once all waypoints needed are added, you can send the mission using the send_mission function. Example :

mavlink->send_mission();

If the mission upload process is successful, you should see this message in the serial monitor : Send Mission

To start the mission, you can use the start_mission function. Example :

mavlink->start_mission();

The drone will arm itself and change mode to AUTO. The drone will then fly to the first waypoint. Once the drone reaches the first waypoint, it will fly to the next waypoint and so on. Once the drone reaches the last waypoint, it will return to home position and land.

More detailed explanation on the communication and mission protocol can be found in the official mavlink documentation

The function read_data() should be called in the loop() function, as it needs to constantly check if RX pin has available data from the FMU. Example :

void loop(){
    mavlink->read_data();
}

The function send_heartbeat() should also be called once every second. The library Task Scheduler is used to schedule the function to be called once every second. Example :

#include <TaskScheduler.h>
#include <mavlink_commands.hpp>

Scheduler taskScheduler;

std::shared_ptr<Task> heartbeat_task;
std::shared_ptr<MAVLink> mavlink;

void heartbeat_task_callback(){
    mavlink->send_heartbeat();
}

void setup(){
    mavlink = std::make_shared<MAVLink>(57600, 16, 17);

    heartbeat_task = std::make_shared<Task>(TASK_SECOND, TASK_FOREVER, &heartbeat_task_callback);
    taskScheduler.addTask(*heartbeat_task);
    heartbeat_task->enable();
}

void loop(){
    mavlink->read_data();
    taskScheduler.execute();
}

About

Arduino/ESP-32 MAVLink C++ Library

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • C 99.0%
  • C++ 1.0%