47 #if defined(MEMORY_CONSTRAINED_SYSTEM) 48 # define NUM_MISSIONS_SUPPORTED 50 49 #elif defined(__PX4_POSIX) 50 # define NUM_MISSIONS_SUPPORTED (UINT16_MAX-1) // This is allocated as needed. 52 # define NUM_MISSIONS_SUPPORTED 2000 // This allocates a file of around 181 kB on the SD card. 55 #define NAV_EPSILON_POSITION 0.001f 139 #if (__GNUC__ >= 5) || __clang__ 141 #pragma GCC diagnostic push 142 #pragma GCC diagnostic error "-Wpadded" 143 #endif // GCC >= 5 || Clang 232 #if (__GNUC__ >= 5) || __clang__ 233 #pragma GCC diagnostic pop 234 #endif // GCC >= 5 || Clang
Global position setpoint in WGS84 coordinates.
uint16_t frame
mission frame
uint16_t vertex_count
Polygon vertex count (geofence)
float altitude
altitude in meters (AMSL)
uint16_t autocontinue
true if next waypoint should follow after this one
float acceptance_radius
default radius in which the mission is accepted as reached in meters
uint16_t vtol_back_transition
part of the vtol back transition sequence
uint16_t origin
how the mission item was generated
uint16_t vertex_count
number of vertices in this polygon
uint16_t do_jump_repeat_count
how many times do jump needs to be done
float circle_radius
geofence circle radius in meters (only used for NAV_CMD_NAV_FENCE_CIRCLE*)
double lon
longitude in degrees
float ___lat_float
padding
float ___lon_float
padding
uint16_t _padding0
padding remaining unused bits
float circle_radius
geofence circle radius in meters (only used for NAV_CMD_NAV_FENCE_CIRCLE*)
uint16_t nav_cmd
navigation command
uint16_t do_jump_current_count
count how many times the jump has been done
dataman housekeeping information for a specific item.
float time_inside
time that the MAV should stay inside the radius before advancing in seconds
Safe Point (Rally Point).
float params[7]
array to store mission command values for MAV_FRAME_MISSION
uint16_t land_precision
Defines if landing should be precise: 0 = normal landing, 1 = opportunistic precision landing...
uint16_t nav_cmd
navigation command (one of MAV_CMD_NAV_FENCE_*)
uint16_t num_items
total number of items stored (excluding this one)
int16_t do_jump_mission_index
index where the do jump will go to
uint16_t update_counter
This counter is increased when (some) items change (this can wrap)
float pitch_min
minimal pitch angle for fixed wing takeoff waypoints
uint16_t loiter_exit_xtrack
exit xtrack location: 0 for center of loiter wp, 1 for exit location
uint8_t _padding1[2]
padding struct size to alignment boundary
uint16_t force_heading
heading needs to be reached
float yaw
in radians NED -PI..+PI, NAN means don't change yaw
float loiter_radius
loiter radius in meters, 0 for a VTOL to hover, negative for counter-clockwise
uint16_t altitude_is_relative
true if altitude is relative from start point
double lat
latitude in degrees