Soletta™ Framework
|
#include <sol-log.h>
#include <sol-mainloop.h>
#include <sol-mavlink.h>
#include <sol-util.h>
#include <stdio.h>
Macros | |
#define | TAKEOFF_ALT 10 |
Functions | |
static void | armed_cb (void *data, struct sol_mavlink *mavlink) |
static void | disarmed_cb (void *data, struct sol_mavlink *mavlink) |
int | main (int argc, char *argv[]) |
static void | mavlink_connect_cb (void *data, struct sol_mavlink *mavlink) |
static void | mission_reached_cb (void *data, struct sol_mavlink *mavlink) |
static void | mode_changed_cb (void *data, struct sol_mavlink *mavlink) |
static void | position_changed_cb (void *data, struct sol_mavlink *mavlink) |
static void | takeoff (struct sol_mavlink *mavlink) |
#define TAKEOFF_ALT 10 |
Referenced by takeoff().
|
static |
References SOL_DBG, sol_mavlink_get_mode(), SOL_MAVLINK_MODE_GUIDED, and takeoff().
Referenced by main().
|
static |
References sol_mavlink_get_mode(), and SOL_MAVLINK_MODE_LAND.
Referenced by main().
int main | ( | int | argc, |
char * | argv[] | ||
) |
References sol_mavlink_handlers::api_version, sol_mavlink_config::api_version, armed_cb(), disarmed_cb(), mavlink_connect_cb(), mission_reached_cb(), mode_changed_cb(), position_changed_cb(), SOL_ERR, sol_init(), SOL_MAVLINK_CONFIG_API_VERSION, sol_mavlink_connect(), sol_mavlink_disconnect(), SOL_MAVLINK_HANDLERS_API_VERSION, sol_run(), SOL_SET_API_VERSION, and sol_shutdown().
|
static |
References SOL_ERR, SOL_INF, sol_mavlink_get_mode(), sol_mavlink_is_armed(), SOL_MAVLINK_MODE_GUIDED, sol_mavlink_set_armed(), sol_mavlink_set_mode(), sol_util_strerrora, and takeoff().
Referenced by main().
|
static |
References SOL_ERR, sol_mavlink_get_home_position(), sol_mavlink_get_mode(), sol_mavlink_land(), SOL_MAVLINK_MODE_GUIDED, and sol_util_strerrora.
Referenced by main().
|
static |
References SOL_ERR, sol_mavlink_get_mode(), sol_mavlink_is_armed(), SOL_MAVLINK_MODE_GUIDED, sol_mavlink_set_armed(), and sol_util_strerrora.
Referenced by main().
|
static |
References sol_mavlink_position::altitude, sol_mavlink_position::latitude, sol_mavlink_position::longitude, SOL_ERR, sol_mavlink_get_current_position(), sol_mavlink_is_armed(), and sol_util_strerrora.
Referenced by main().
|
static |
References sol_mavlink_position::altitude, SOL_ERR, sol_mavlink_take_off(), sol_util_strerrora, and TAKEOFF_ALT.
Referenced by armed_cb(), and mavlink_connect_cb().