|
Soletta™ Framework
|
Mavlink callback handlers. More...
#include <sol-mavlink.h>
Data Fields | |
| uint16_t | api_version |
| Should always be set to SOL_MAVLINK_HANDLERS_API_VERSION. More... | |
| void(* | armed )(void *data, struct sol_mavlink *mavlink) |
| On armed callback. More... | |
| void(* | connect )(void *data, struct sol_mavlink *mavlink) |
| On connect callback. More... | |
| void(* | disarmed )(void *data, struct sol_mavlink *mavlink) |
| On armed callback. More... | |
| void(* | mission_reached )(void *data, struct sol_mavlink *mavlink) |
| On destination reached callback. More... | |
| void(* | mode_changed )(void *data, struct sol_mavlink *mavlink) |
| On mode changed callback. More... | |
| void(* | position_changed )(void *data, struct sol_mavlink *mavlink) |
| On position changed callback. More... | |
Mavlink callback handlers.
| uint16_t sol_mavlink_handlers::api_version |
Should always be set to SOL_MAVLINK_HANDLERS_API_VERSION.
Referenced by main().
| void(* sol_mavlink_handlers::armed)(void *data, struct sol_mavlink *mavlink) |
On armed callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when the vehicle has been armed, no matter if it was armed by your application or not
| void(* sol_mavlink_handlers::connect)(void *data, struct sol_mavlink *mavlink) |
On connect callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when a connect request has been processed
| void(* sol_mavlink_handlers::disarmed)(void *data, struct sol_mavlink *mavlink) |
On armed callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when the vehicle has been disarmed, no matter if it was disarmed by your application or not
| void(* sol_mavlink_handlers::mission_reached)(void *data, struct sol_mavlink *mavlink) |
On destination reached callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when the vehicle has reached the current mission's destination.
| void(* sol_mavlink_handlers::mode_changed)(void *data, struct sol_mavlink *mavlink) |
On mode changed callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when a mode change has been processed
| void(* sol_mavlink_handlers::position_changed)(void *data, struct sol_mavlink *mavlink) |
On position changed callback.
| data | User provided data |
| mavlink | Mavlink Object |
Callback called when the vehicle has changed its position, no matter if it was moved by your application or not
1.8.6