Firmware
Public Attributes | List of all members
mission_item_s Struct Reference

Global position setpoint in WGS84 coordinates. More...

#include <navigation.h>

Public Attributes

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

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


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