Soletta™ Framework
Framework for making IoT devices

Full online documentation | C API Index
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
Data Structures | Typedefs | Enumerations | Functions

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_mavlinksol_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...
 

Detailed Description

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.

Warning
Experimental API. Changes are expected in future releases.

Typedef Documentation

Mavlink Object.

See Also
sol_mavlink_connect

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.

Server Configuration.

Mavlink callback handlers.

Mavlink position structure.

Enumeration Type Documentation

Mavlink flight modes.

Enumerator
SOL_MAVLINK_MODE_ACRO 

Acro mode (Rate mode) uses the RC sticks to control the angular velocity of the copter.

SOL_MAVLINK_MODE_ALT_HOLD 

In altitude hold mode, Copter maintains a consistent altitude while allowing roll, pitch, and yaw to be controlled normally.

SOL_MAVLINK_MODE_ALTITUDE 
SOL_MAVLINK_MODE_AUTO 

In Auto mode the copter will follow a pre-programmed mission script stored in the autopilot which is made up of navigation commands (i.e.

waypoints) and “do” commands (i.e. commands that do not affect the location of the copter including triggering a camera shutter).

SOL_MAVLINK_MODE_AUTO_TUNE 
SOL_MAVLINK_MODE_CIRCLE 

In circle mode the copter will orbit a point of interest with the nose of the vehicle pointed towards the center.

SOL_MAVLINK_MODE_CRUISE 
SOL_MAVLINK_MODE_DRIFT 

Drift Mode allows the user to fly a multi-copter as if it were a plane with built in automatic coordinated turns.

SOL_MAVLINK_MODE_EASY 
SOL_MAVLINK_MODE_FBWA 
SOL_MAVLINK_MODE_FBWB 
SOL_MAVLINK_MODE_FLIP 
SOL_MAVLINK_MODE_GUIDED 

Guided mode is a capability of Copter to dynamically guide the copter to a target location wirelessly using a telemetry radio module, ground station application or a companion board application.

SOL_MAVLINK_MODE_HOLD 
SOL_MAVLINK_MODE_INITIALISING 
SOL_MAVLINK_MODE_LAND 

Land mode attempts to bring the copter straight down.

SOL_MAVLINK_MODE_LEARNING 
SOL_MAVLINK_MODE_LOITER 

Loiter mode automatically attempts to maintain the current location, heading and altitude.

SOL_MAVLINK_MODE_MANUAL 
SOL_MAVLINK_MODE_OF_LOITER 
SOL_MAVLINK_MODE_POS_HOLD 

It is similar to Loiter in that the vehicle maintains a constant location, heading, and altitude but is generally more popular because the pilot stick inputs directly control the vehicle’s lean angle providing a more “natural” feel.

SOL_MAVLINK_MODE_POSITION 

Position mode is the same as loiter mode, but with manual throttle control.

SOL_MAVLINK_MODE_RTL 

RTL mode (Return To Launch mode) navigates Copter from its current position to hover above the home position.

SOL_MAVLINK_MODE_SCAN 
SOL_MAVLINK_MODE_SPORT 

Sport Mode is also known as “rate controlled stabilize” plus Altitude Hold.

SOL_MAVLINK_MODE_STABILIZE 

Stabilize mode allows you to fly your vehicle manually, but self-levels the roll and pitch axis.

SOL_MAVLINK_MODE_STEERING 
SOL_MAVLINK_MODE_STOP 
SOL_MAVLINK_MODE_TRAINING 
SOL_MAVLINK_MODE_UNKNOWN 

Function Documentation

int sol_mavlink_change_speed ( struct sol_mavlink mavlink,
float  speed,
bool  airspeed 
)

Change the vehicle speed.

Parameters
mavlinkMavlink Object;
speedThe desired speed in m/s;
airspeedTrue if speed in airspeed, groundspeed is used otherwise;
Returns
0 on success, -EINVAL on invalid argument, -errno on error
struct sol_mavlink* sol_mavlink_connect ( const char *  addr,
const struct sol_mavlink_config config,
const void *  data 
)

Connect to a mavlink server.

Parameters
addrThe target mavlink server address
configConfiguration and callbacks
dataUser data provided to the callbacks
Returns
New mavlink object on success, NULL otherwise

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

Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by main().

void sol_mavlink_disconnect ( struct sol_mavlink mavlink)

Disconnect from mavlink server.

Parameters
mavlinkMavlink Object;
See Also
sol_mavlink_connect

Terminate the connection with the mavlink server and free the resources associated to the mavlink object.

Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by main().

int sol_mavlink_get_current_position ( struct sol_mavlink mavlink,
struct sol_mavlink_position pos 
)

Get the vehicle's current position.

Parameters
mavlinkMavlink Object;
possol_mavlink_position pointer to set the positions values to;
Returns
0 on success, -EINVAL on invalid argument
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

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.

Parameters
mavlinkMavlink Object;
possol_mavlink_position pointer to set the positions values to;
Returns
0 on success, -EINVAL on invalid argument

Home position represents the location and altitude where the vehicle took off from.

Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by mission_reached_cb().

enum sol_mavlink_mode sol_mavlink_get_mode ( struct sol_mavlink mavlink)

Get the current vehicle's mode.

Parameters
mavlinkMavlink Object;
See Also
sol_mavlink_set_mode
sol_mavlink_mode
Returns
The current vehicle's mode
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

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.

Parameters
mavlinkMavlink Object;
possol_mavlink_position The position where the vehicle should go to;
Returns
0 on success, -EINVAL on invalid argument, -errno on error
Examples:
/src/samples/mavlink/goto.c.

Referenced by mission_reached_cb().

bool sol_mavlink_is_armed ( struct sol_mavlink mavlink)

Check if the vehicle is currently armed.

Parameters
mavlinkMavlink Object;
See Also
sol_mavlink_set_armed
Returns
true the vehicle is currently armed, false otherwise
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

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.

Parameters
mavlinkMavlink Object;
possol_mavlink_position The position where it should land to;
Returns
0 on success, -EINVAL on invalid argument, -errno on error
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by mission_reached_cb().

int sol_mavlink_set_armed ( struct sol_mavlink mavlink,
bool  armed 
)

Set the vehicle to armed or not.

Parameters
mavlinkMavlink Object;
armedtrue to set as armed, false otherwise;
See Also
sol_mavlink_is_armed
Returns
0 on success, -EINVAL on invalid argument, -errno on error
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

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.

Parameters
mavlinkMavlink Object;
modeThe mode to be set;
See Also
sol_mavlink_get_mode
sol_mavlink_mode
Returns
0 on success, -EINVAL on invalid argument, -errno on error
Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by mavlink_connect_cb().

int sol_mavlink_take_off ( struct sol_mavlink mavlink,
struct sol_mavlink_position pos 
)

Takeoff the vehicle.

Parameters
mavlinkMavlink Object;
posThe target position;
See Also
sol_mavlink_set_armed
sol_mavlink_is_armed
sol_mavlink_get_mode
SOL_MAVLINK_MODE_GUIDED
Returns
0 on success, -EINVAL on invalid argument, -errno on error

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.

Examples:
/src/samples/mavlink/basic.c, and /src/samples/mavlink/goto.c.

Referenced by takeoff().