mavsdk::MissionRaw::MavlinkMissionItemInt Struct Reference
#include: mission_raw.h
Mission item identical to MAVLink MISSION_ITEM_INT.
Data Fields
uint8_t target_system - System ID.
uint8_t target_component - Component ID.
uint16_t seq - Sequence.
uint8_t frame - The coordinate system of the waypoint.
uint16_t command - The scheduled action for the waypoint.
uint8_t current - false:0, true:1.
uint8_t autocontinue - Autocontinue to next waypoint.
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).
uint8_t mission_type - Mission type.
Field Documentation
target_system
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::target_system
System ID.
target_component
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::target_component
Component ID.
seq
uint16_t mavsdk::MissionRaw::MavlinkMissionItemInt::seq
Sequence.
frame
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::frame
The coordinate system of the waypoint.
command
uint16_t mavsdk::MissionRaw::MavlinkMissionItemInt::command
The scheduled action for the waypoint.
current
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::current
false:0, true:1.
autocontinue
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::autocontinue
Autocontinue to next waypoint.
param1
float mavsdk::MissionRaw::MavlinkMissionItemInt::param1
PARAM1, see MAV_CMD enum.
param2
float mavsdk::MissionRaw::MavlinkMissionItemInt::param2
PARAM2, see MAV_CMD enum.
param3
float mavsdk::MissionRaw::MavlinkMissionItemInt::param3
PARAM3, see MAV_CMD enum.
param4
float mavsdk::MissionRaw::MavlinkMissionItemInt::param4
PARAM4, see MAV_CMD enum.
x
int32_t mavsdk::MissionRaw::MavlinkMissionItemInt::x
PARAM5 / local: x position in meters 1e4, global: latitude in degrees 10^7.
y
int32_t mavsdk::MissionRaw::MavlinkMissionItemInt::y
PARAM6 / y position: local: x position in meters 1e4, global: longitude in degrees 10^7.
z
float mavsdk::MissionRaw::MavlinkMissionItemInt::z
PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
mission_type
uint8_t mavsdk::MissionRaw::MavlinkMissionItemInt::mission_type
Mission type.