mavsdk::MissionRaw::MissionItem Struct Reference

#include: mission_raw.h


Mission item exactly identical to MAVLink MISSION_ITEM_INT.

Data Fields

uint32_t seq {} - Sequence (uint16_t)

uint32_t frame {} - The coordinate system of the waypoint (actually uint8_t)

uint32_t command {} - The scheduled action for the waypoint (actually uint16_t)

uint32_t current {} - false:0, true:1 (actually uint8_t)

uint32_t autocontinue {} - Autocontinue to next waypoint (actually uint8_t)

float param1 {} - PARAM1, see MAV_CMD enum.

float param2 {} - PARAM2, see MAV_CMD enum.

float param3 {} - PARAM3, see MAV_CMD enum.

float param4 {} - PARAM4, see MAV_CMD enum.

int32_t x {} - PARAM5 / local: x position in meters 1e4, global: latitude in degrees 10^7.

int32_t y {} - PARAM6 / y position: local: x position in meters 1e4, global: longitude in degrees 10^7.

float z {} - PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)

uint32_t mission_type {} - Mission type (actually uint8_t)

Field Documentation

seq

uint32_t mavsdk::MissionRaw::MissionItem::seq {}

Sequence (uint16_t)

frame

uint32_t mavsdk::MissionRaw::MissionItem::frame {}

The coordinate system of the waypoint (actually uint8_t)

command

uint32_t mavsdk::MissionRaw::MissionItem::command {}

The scheduled action for the waypoint (actually uint16_t)

current

uint32_t mavsdk::MissionRaw::MissionItem::current {}

false:0, true:1 (actually uint8_t)

autocontinue

uint32_t mavsdk::MissionRaw::MissionItem::autocontinue {}

Autocontinue to next waypoint (actually uint8_t)

param1

float mavsdk::MissionRaw::MissionItem::param1 {}

PARAM1, see MAV_CMD enum.

param2

float mavsdk::MissionRaw::MissionItem::param2 {}

PARAM2, see MAV_CMD enum.

param3

float mavsdk::MissionRaw::MissionItem::param3 {}

PARAM3, see MAV_CMD enum.

param4

float mavsdk::MissionRaw::MissionItem::param4 {}

PARAM4, see MAV_CMD enum.

x

int32_t mavsdk::MissionRaw::MissionItem::x {}

PARAM5 / local: x position in meters 1e4, global: latitude in degrees 10^7.

y

int32_t mavsdk::MissionRaw::MissionItem::y {}

PARAM6 / y position: local: x position in meters 1e4, global: longitude in degrees 10^7.

z

float mavsdk::MissionRaw::MissionItem::z {}

PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)

mission_type

uint32_t mavsdk::MissionRaw::MissionItem::mission_type {}

Mission type (actually uint8_t)

© MAVSDK Development Team 2017-2023. License: CC BY 4.0            Updated: 2023-12-27 03:58:12

results matching ""

    No results matching ""