static void mavlink_connect_cb(void *data, struct sol_mavlink *mavlink) { int err; enum sol_mavlink_mode mode; SOL_INF("mavlink connection stablished"); mode = sol_mavlink_get_mode(mavlink); if (mode != SOL_MAVLINK_MODE_GUIDED) { err = sol_mavlink_set_mode(mavlink, SOL_MAVLINK_MODE_GUIDED); if (err < 0) { SOL_ERR("Could not set mode: %s", sol_util_strerrora(-err)); } return; } if (!sol_mavlink_is_armed(mavlink)) { err = sol_mavlink_set_armed(mavlink, true); if (err < 0) { SOL_ERR("Could not arm vechicle: %s", sol_util_strerrora(-err)); } return; } takeoff(mavlink); }
static void mode_changed_cb(void *data, struct sol_mavlink *mavlink) { int err; enum sol_mavlink_mode mode = sol_mavlink_get_mode(mavlink); bool armed = sol_mavlink_is_armed(mavlink); if (mode == SOL_MAVLINK_MODE_GUIDED && !armed) { err = sol_mavlink_set_armed(mavlink, true); if (err < 0) { SOL_ERR("Could not arm vechicle: %s", sol_util_strerrora(-err)); } } }
static void position_changed_cb(void *data, struct sol_mavlink *mavlink) { int err; struct sol_mavlink_position pos; err = sol_mavlink_get_current_position(mavlink, &pos); if (err < 0) { SOL_ERR("Could not get current position: %s", sol_util_strerrora(-err)); return; } if (sol_mavlink_is_armed(mavlink)) printf("lat: %f, long: %f, alt: %f\n", pos.latitude, pos.longitude, pos.altitude); }
SOL_API int sol_mavlink_set_armed(struct sol_mavlink *mavlink, bool armed) { mavlink_message_t msg = { 0 }; uint8_t buf[MAVLINK_MAX_PACKET_LEN]; uint16_t len, res; bool curr; SOL_NULL_CHECK(mavlink, -EINVAL); curr = sol_mavlink_is_armed(mavlink); SOL_EXP_CHECK(curr == !!armed, -EINVAL); mavlink_msg_command_long_pack(mavlink->sysid, mavlink->compid, &msg, 0, 0, MAV_CMD_COMPONENT_ARM_DISARM, 0, !!armed, 0, 0, 0, 0, 0, 0); len = mavlink_msg_to_send_buffer(buf, &msg); res = write(mavlink->fd, buf, len); SOL_INT_CHECK(res, < len, -errno); return 0; }