195 #ifndef SOL_NO_API_VERSION
196 #define SOL_MAVLINK_HANDLERS_API_VERSION (1)
288 #ifndef SOL_NO_API_VERSION
289 #define SOL_MAVLINK_CONFIG_API_VERSION (1)
Server Configuration.
Definition: sol-mavlink.h:287
Definition: sol-mavlink.h:127
float z
Local Z position of this position in the local coordinate frame.
Definition: sol-mavlink.h:188
Mavlink position structure.
Definition: sol-mavlink.h:171
Definition: sol-mavlink.h:162
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.
Definition: sol-mavlink.h:136
Definition: sol-mavlink.h:149
Definition: sol-mavlink.h:103
struct sol_mavlink * sol_mavlink_connect(const char *addr, const struct sol_mavlink_config *config, const void *data)
Connect to a mavlink server.
enum sol_mavlink_mode sol_mavlink_get_mode(struct sol_mavlink *mavlink)
Get the current vehicle's mode.
void sol_mavlink_disconnect(struct sol_mavlink *mavlink)
Disconnect from mavlink server.
int sol_mavlink_take_off(struct sol_mavlink *mavlink, struct sol_mavlink_position *pos)
Takeoff the vehicle.
Position mode is the same as loiter mode, but with manual throttle control.
Definition: sol-mavlink.h:142
Definition: sol-mavlink.h:120
struct sol_mavlink sol_mavlink
Mavlink Object.
Definition: sol-mavlink.h:57
bool sol_mavlink_is_armed(struct sol_mavlink *mavlink)
Check if the vehicle is currently armed.
int sol_mavlink_get_home_position(struct sol_mavlink *mavlink, struct sol_mavlink_position *pos)
Get the vehicle's home position.
int baud_rate
In case of serial protocol set the baud_rate, default set to 115200.
Definition: sol-mavlink.h:304
sol_mavlink_mode
Mavlink flight modes.
Definition: sol-mavlink.h:64
Definition: sol-mavlink.h:164
float latitude
Latitude in degrees.
Definition: sol-mavlink.h:173
struct sol_mavlink_handlers sol_mavlink_handlers
Mavlink callback handlers.
uint16_t api_version
Should always be set to SOL_MAVLINK_CONFIG_API_VERSION.
Definition: sol-mavlink.h:293
struct sol_mavlink_config sol_mavlink_config
Server Configuration.
Sport Mode is also known as “rate controlled stabilize” plus Altitude Hold.
Definition: sol-mavlink.h:155
Mavlink callback handlers.
Definition: sol-mavlink.h:194
void(* mode_changed)(void *data, struct sol_mavlink *mavlink)
On mode changed callback.
Definition: sol-mavlink.h:225
Acro mode (Rate mode) uses the RC sticks to control the angular velocity of the copter.
Definition: sol-mavlink.h:69
const struct sol_mavlink_handlers * handlers
Handlers to be used with this connection.
Definition: sol-mavlink.h:299
int sol_mavlink_change_speed(struct sol_mavlink *mavlink, float speed, bool airspeed)
Change the vehicle speed.
Definition: sol-mavlink.h:128
void(* disarmed)(void *data, struct sol_mavlink *mavlink)
On armed callback.
Definition: sol-mavlink.h:253
void(* armed)(void *data, struct sol_mavlink *mavlink)
On armed callback.
Definition: sol-mavlink.h:239
Definition: sol-mavlink.h:104
Definition: sol-mavlink.h:86
float altitude
Altitude in meters.
Definition: sol-mavlink.h:179
RTL mode (Return To Launch mode) navigates Copter from its current position to hover above the home p...
Definition: sol-mavlink.h:148
int sol_mavlink_set_mode(struct sol_mavlink *mavlink, enum sol_mavlink_mode mode)
Set the vehicle mode.
int sol_mavlink_get_current_position(struct sol_mavlink *mavlink, struct sol_mavlink_position *pos)
Get the vehicle's current position.
Guided mode is a capability of Copter to dynamically guide the copter to a target location wirelessly...
Definition: sol-mavlink.h:112
int sol_mavlink_land(struct sol_mavlink *mavlink, struct sol_mavlink_position *pos)
Land the vehicle's.
Drift Mode allows the user to fly a multi-copter as if it were a plane with built in automatic coordi...
Definition: sol-mavlink.h:100
Stabilize mode allows you to fly your vehicle manually, but self-levels the roll and pitch axis...
Definition: sol-mavlink.h:161
Loiter mode automatically attempts to maintain the current location, heading and altitude.
Definition: sol-mavlink.h:126
In circle mode the copter will orbit a point of interest with the nose of the vehicle pointed towards...
Definition: sol-mavlink.h:92
uint16_t api_version
Should always be set to SOL_MAVLINK_HANDLERS_API_VERSION.
Definition: sol-mavlink.h:200
Definition: sol-mavlink.h:163
In Auto mode the copter will follow a pre-programmed mission script stored in the autopilot which is ...
Definition: sol-mavlink.h:84
float x
Local X position of this position in the local coordinate frame.
Definition: sol-mavlink.h:182
Definition: sol-mavlink.h:105
Definition: sol-mavlink.h:114
int sol_mavlink_set_armed(struct sol_mavlink *mavlink, bool armed)
Set the vehicle to armed or not.
Definition: sol-mavlink.h:94
float longitude
Longitude in degrees.
Definition: sol-mavlink.h:176
void(* connect)(void *data, struct sol_mavlink *mavlink)
On connect callback.
Definition: sol-mavlink.h:213
Definition: sol-mavlink.h:76
Definition: sol-mavlink.h:102
Definition: sol-mavlink.h:113
int sol_mavlink_go_to(struct sol_mavlink *mavlink, struct sol_mavlink_position *pos)
Navigate to a given location.
void(* position_changed)(void *data, struct sol_mavlink *mavlink)
On position changed callback.
Definition: sol-mavlink.h:267
void(* mission_reached)(void *data, struct sol_mavlink *mavlink)
On destination reached callback.
Definition: sol-mavlink.h:281
Land mode attempts to bring the copter straight down.
Definition: sol-mavlink.h:119
Definition: sol-mavlink.h:165
float y
Local Y position of this position in the local coordinate frame.
Definition: sol-mavlink.h:185
In altitude hold mode, Copter maintains a consistent altitude while allowing roll, pitch, and yaw to be controlled normally.
Definition: sol-mavlink.h:75
struct sol_mavlink_position sol_mavlink_position
Mavlink position structure.