Soletta™ Framework
|
MAVLink or Micro Air Vehicle Link is a protocol for communicating with small unmanned vehicles. More...
Data Structures | |
struct | sol_mavlink_config |
Server Configuration. More... | |
struct | sol_mavlink_handlers |
Mavlink callback handlers. More... | |
struct | sol_mavlink_position |
Mavlink position structure. More... | |
Typedefs | |
typedef struct sol_mavlink | sol_mavlink |
Mavlink Object. More... | |
typedef struct sol_mavlink_config | sol_mavlink_config |
Server Configuration. More... | |
typedef struct sol_mavlink_handlers | sol_mavlink_handlers |
Mavlink callback handlers. More... | |
typedef struct sol_mavlink_position | sol_mavlink_position |
Mavlink position structure. More... | |
Enumerations | |
enum | sol_mavlink_mode { SOL_MAVLINK_MODE_ACRO = 1, SOL_MAVLINK_MODE_ALT_HOLD = 2, SOL_MAVLINK_MODE_ALTITUDE = 3, SOL_MAVLINK_MODE_AUTO = 4, SOL_MAVLINK_MODE_AUTO_TUNE = 5, SOL_MAVLINK_MODE_CIRCLE = 6, SOL_MAVLINK_MODE_CRUISE = 7, SOL_MAVLINK_MODE_DRIFT = 8, SOL_MAVLINK_MODE_EASY = 9, SOL_MAVLINK_MODE_FBWA = 10, SOL_MAVLINK_MODE_FBWB = 11, SOL_MAVLINK_MODE_FLIP = 12, SOL_MAVLINK_MODE_GUIDED = 13, SOL_MAVLINK_MODE_HOLD = 14, SOL_MAVLINK_MODE_INITIALISING = 15, SOL_MAVLINK_MODE_LAND = 16, SOL_MAVLINK_MODE_LEARNING = 17, SOL_MAVLINK_MODE_LOITER = 18, SOL_MAVLINK_MODE_MANUAL = 19, SOL_MAVLINK_MODE_OF_LOITER = 20, SOL_MAVLINK_MODE_POS_HOLD = 21, SOL_MAVLINK_MODE_POSITION = 22, SOL_MAVLINK_MODE_RTL = 23, SOL_MAVLINK_MODE_SCAN = 24, SOL_MAVLINK_MODE_SPORT = 25, SOL_MAVLINK_MODE_STABILIZE = 26, SOL_MAVLINK_MODE_STEERING = 27, SOL_MAVLINK_MODE_STOP = 28, SOL_MAVLINK_MODE_TRAINING = 29, SOL_MAVLINK_MODE_UNKNOWN = 30 } |
Mavlink flight modes. More... | |
Functions | |
int | sol_mavlink_change_speed (struct sol_mavlink *mavlink, float speed, bool airspeed) |
Change the vehicle speed. More... | |
struct sol_mavlink * | sol_mavlink_connect (const char *addr, const struct sol_mavlink_config *config, const void *data) |
Connect to a mavlink server. More... | |
void | sol_mavlink_disconnect (struct sol_mavlink *mavlink) |
Disconnect from mavlink server. More... | |
int | sol_mavlink_get_current_position (struct sol_mavlink *mavlink, struct sol_mavlink_position *pos) |
Get the vehicle's current position. More... | |
int | sol_mavlink_get_home_position (struct sol_mavlink *mavlink, struct sol_mavlink_position *pos) |
Get the vehicle's home position. More... | |
enum sol_mavlink_mode | sol_mavlink_get_mode (struct sol_mavlink *mavlink) |
Get the current vehicle's mode. More... | |
int | sol_mavlink_go_to (struct sol_mavlink *mavlink, struct sol_mavlink_position *pos) |
Navigate to a given location. More... | |
bool | sol_mavlink_is_armed (struct sol_mavlink *mavlink) |
Check if the vehicle is currently armed. More... | |
int | sol_mavlink_land (struct sol_mavlink *mavlink, struct sol_mavlink_position *pos) |
Land the vehicle's. More... | |
int | sol_mavlink_set_armed (struct sol_mavlink *mavlink, bool armed) |
Set the vehicle to armed or not. More... | |
int | sol_mavlink_set_mode (struct sol_mavlink *mavlink, enum sol_mavlink_mode mode) |
Set the vehicle mode. More... | |
int | sol_mavlink_take_off (struct sol_mavlink *mavlink, struct sol_mavlink_position *pos) |
Takeoff the vehicle. More... | |
MAVLink or Micro Air Vehicle Link is a protocol for communicating with small unmanned vehicles.
It is designed as a header-only message marshaling library.
Mavlink Object.
This object is the abstraction of a Mavlink connection. This is the base structure for all Mavlink operations and is obtained through the sol_mavlink_connect() API.
typedef struct sol_mavlink_config sol_mavlink_config |
Server Configuration.
typedef struct sol_mavlink_handlers sol_mavlink_handlers |
Mavlink callback handlers.
typedef struct sol_mavlink_position sol_mavlink_position |
Mavlink position structure.
enum sol_mavlink_mode |
Mavlink flight modes.
int sol_mavlink_change_speed | ( | struct sol_mavlink * | mavlink, |
float | speed, | ||
bool | airspeed | ||
) |
Change the vehicle speed.
mavlink | Mavlink Object; |
speed | The desired speed in m/s; |
airspeed | True if speed in airspeed, groundspeed is used otherwise; |
struct sol_mavlink* sol_mavlink_connect | ( | const char * | addr, |
const struct sol_mavlink_config * | config, | ||
const void * | data | ||
) |
Connect to a mavlink server.
addr | The target mavlink server address |
config | Configuration and callbacks |
data | User data provided to the callbacks |
The addr argument is composed of protocol:address:port where port is optional depending on protocol.
Currently supported protocols are tcp and serial, valid addr would be: tcp:localhost:5726 serial:/dev/ttyUSB0
Referenced by main().
void sol_mavlink_disconnect | ( | struct sol_mavlink * | mavlink | ) |
Disconnect from mavlink server.
mavlink | Mavlink Object; |
Terminate the connection with the mavlink server and free the resources associated to the mavlink object.
Referenced by main().
int sol_mavlink_get_current_position | ( | struct sol_mavlink * | mavlink, |
struct sol_mavlink_position * | pos | ||
) |
Get the vehicle's current position.
mavlink | Mavlink Object; |
pos | sol_mavlink_position pointer to set the positions values to; |
Referenced by mission_reached_cb(), and position_changed_cb().
int sol_mavlink_get_home_position | ( | struct sol_mavlink * | mavlink, |
struct sol_mavlink_position * | pos | ||
) |
Get the vehicle's home position.
mavlink | Mavlink Object; |
pos | sol_mavlink_position pointer to set the positions values to; |
Home position represents the location and altitude where the vehicle took off from.
Referenced by mission_reached_cb().
enum sol_mavlink_mode sol_mavlink_get_mode | ( | struct sol_mavlink * | mavlink | ) |
Get the current vehicle's mode.
mavlink | Mavlink Object; |
Referenced by armed_cb(), disarmed_cb(), mavlink_connect_cb(), mission_reached_cb(), and mode_changed_cb().
int sol_mavlink_go_to | ( | struct sol_mavlink * | mavlink, |
struct sol_mavlink_position * | pos | ||
) |
Navigate to a given location.
mavlink | Mavlink Object; |
pos | sol_mavlink_position The position where the vehicle should go to; |
Referenced by mission_reached_cb().
bool sol_mavlink_is_armed | ( | struct sol_mavlink * | mavlink | ) |
Check if the vehicle is currently armed.
mavlink | Mavlink Object; |
Referenced by mavlink_connect_cb(), mode_changed_cb(), and position_changed_cb().
int sol_mavlink_land | ( | struct sol_mavlink * | mavlink, |
struct sol_mavlink_position * | pos | ||
) |
Land the vehicle's.
mavlink | Mavlink Object; |
pos | sol_mavlink_position The position where it should land to; |
Referenced by mission_reached_cb().
int sol_mavlink_set_armed | ( | struct sol_mavlink * | mavlink, |
bool | armed | ||
) |
Set the vehicle to armed or not.
mavlink | Mavlink Object; |
armed | true to set as armed, false otherwise; |
Referenced by mavlink_connect_cb(), and mode_changed_cb().
int sol_mavlink_set_mode | ( | struct sol_mavlink * | mavlink, |
enum sol_mavlink_mode | mode | ||
) |
Set the vehicle mode.
mavlink | Mavlink Object; |
mode | The mode to be set; |
Referenced by mavlink_connect_cb().
int sol_mavlink_take_off | ( | struct sol_mavlink * | mavlink, |
struct sol_mavlink_position * | pos | ||
) |
Takeoff the vehicle.
mavlink | Mavlink Object; |
pos | The target position; |
This call will attempt to take the vehicle off, for this the vehicle must in SOL_MAVLINK_MODE_GUIDED and armed. If the vehicle has already taken off calling this function will have no effect.
Referenced by takeoff().