PX4 Firmware
PX4 Autopilot Software http://px4.io
mission_item_s Struct Reference

Global position setpoint in WGS84 coordinates. More...

#include <navigation.h>

Collaboration diagram for mission_item_s:

Public Attributes

double lat
 latitude in degrees More...
 
double lon
 longitude in degrees More...
 
union {
   struct {
      union {
         float   time_inside
 time that the MAV should stay inside the radius before advancing in seconds More...
 
         float   pitch_min
 minimal pitch angle for fixed wing takeoff waypoints More...
 
         float   circle_radius
 geofence circle radius in meters (only used for NAV_CMD_NAV_FENCE_CIRCLE*) More...
 
      } 
 
      float   acceptance_radius
 default radius in which the mission is accepted as reached in meters More...
 
      float   loiter_radius
 loiter radius in meters, 0 for a VTOL to hover, negative for counter-clockwise More...
 
      float   yaw
 in radians NED -PI..+PI, NAN means don't change yaw More...
 
      float   ___lat_float
 padding More...
 
      float   ___lon_float
 padding More...
 
      float   altitude
 altitude in meters (AMSL) More...
 
   } 
 
   float   params [7]
 array to store mission command values for MAV_FRAME_MISSION More...
 
}; 
 
uint16_t nav_cmd
 navigation command More...
 
int16_t do_jump_mission_index
 index where the do jump will go to More...
 
uint16_t do_jump_repeat_count
 how many times do jump needs to be done More...
 
union {
   uint16_t   do_jump_current_count
 count how many times the jump has been done More...
 
   uint16_t   vertex_count
 Polygon vertex count (geofence) More...
 
   uint16_t   land_precision
 Defines if landing should be precise: 0 = normal landing, 1 = opportunistic precision landing, 2 = required precision landing (with search) More...
 
}; 
 
struct {
   uint16_t   frame: 4
 mission frame More...
 
   uint16_t   origin: 3
 how the mission item was generated More...
 
   uint16_t   loiter_exit_xtrack: 1
 exit xtrack location: 0 for center of loiter wp, 1 for exit location More...
 
   uint16_t   force_heading: 1
 heading needs to be reached More...
 
   uint16_t   altitude_is_relative: 1
 true if altitude is relative from start point More...
 
   uint16_t   autocontinue: 1
 true if next waypoint should follow after this one More...
 
   uint16_t   vtol_back_transition: 1
 part of the vtol back transition sequence More...
 
   uint16_t   _padding0: 4
 padding remaining unused bits More...
 
}; 
 
uint8_t _padding1 [2]
 padding struct size to alignment boundary More...
 

Detailed Description

Global position setpoint in WGS84 coordinates.

This is the position the MAV is heading towards. If it is of type loiter, the MAV is circling around it with the given loiter radius in meters.

Corresponds to one of the DM_KEY_WAYPOINTS_OFFBOARD_* dataman items

Definition at line 145 of file navigation.h.

Member Data Documentation

◆ @124

union { ... }

◆ @126

union { ... }

◆ @128

struct { ... }

◆ ___lat_float

float mission_item_s::___lat_float

padding

Definition at line 158 of file navigation.h.

◆ ___lon_float

float mission_item_s::___lon_float

padding

Definition at line 159 of file navigation.h.

◆ _padding0

uint16_t mission_item_s::_padding0

padding remaining unused bits

Definition at line 177 of file navigation.h.

◆ _padding1

uint8_t mission_item_s::_padding1[2]

padding struct size to alignment boundary

Definition at line 187 of file navigation.h.

◆ acceptance_radius

◆ altitude

◆ altitude_is_relative

◆ autocontinue

◆ circle_radius

float mission_item_s::circle_radius

◆ do_jump_current_count

uint16_t mission_item_s::do_jump_current_count

count how many times the jump has been done

Definition at line 171 of file navigation.h.

Referenced by MavlinkMissionManager::parse_mavlink_mission_item(), Mission::read_mission_item(), and Mission::reset_mission().

◆ do_jump_mission_index

int16_t mission_item_s::do_jump_mission_index

◆ do_jump_repeat_count

uint16_t mission_item_s::do_jump_repeat_count

◆ force_heading

◆ frame

◆ land_precision

uint16_t mission_item_s::land_precision

Defines if landing should be precise: 0 = normal landing, 1 = opportunistic precision landing, 2 = required precision landing (with search)

Definition at line 173 of file navigation.h.

Referenced by MavlinkMissionManager::format_mavlink_mission_item(), MavlinkMissionManager::parse_mavlink_mission_item(), and Mission::set_mission_items().

◆ lat

◆ loiter_exit_xtrack

uint16_t mission_item_s::loiter_exit_xtrack

exit xtrack location: 0 for center of loiter wp, 1 for exit location

Definition at line 177 of file navigation.h.

Referenced by MavlinkMissionManager::format_mavlink_mission_item(), MissionBlock::is_mission_item_reached(), and MavlinkMissionManager::parse_mavlink_mission_item().

◆ loiter_radius

◆ lon

◆ nav_cmd

◆ origin

◆ params

◆ pitch_min

float mission_item_s::pitch_min

◆ time_inside

◆ vertex_count

◆ vtol_back_transition

uint16_t mission_item_s::vtol_back_transition

part of the vtol back transition sequence

Definition at line 177 of file navigation.h.

Referenced by MissionBlock::is_mission_item_reached(), and Mission::set_mission_items().

◆ yaw


The documentation for this struct was generated from the following file: