MAV'RIC
Public Member Functions | Protected Attributes
Waypoint Class Reference

List of all members.

Public Member Functions

 Waypoint ()
 Creates a blank waypoint.
 Waypoint (mavlink_mission_item_t &packet)
 Initialize the waypoint handler.
 Waypoint (uint8_t frame, uint16_t command, uint8_t autocontinue, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
 Initialize the waypoint handler.
void send (const Mavlink_stream &mavlink_stream, uint32_t sysid, const mavlink_message_t *msg, uint16_t seq, uint8_t current)
 Sends a given waypoint via a MAVLink message.
uint8_t frame () const
 Gets the frame of the waypoint.
uint16_t command () const
 Gets the command of the waypoint.
uint8_t autocontinue () const
 Gets the autocontinue state of the waypoint.
float param1 () const
 Gets param1 of the waypoint.
float param2 () const
 Gets param2 of the waypoint.
float param3 () const
 Gets param3 of the waypoint.
float param4 () const
 Gets param4 of the waypoint.
float param5 () const
 Gets param5 of the waypoint.
float param6 () const
 Gets param6 of the waypoint.
float param7 () const
 Gets param7 of the waypoint.
bool heading (float &heading) const
 Gets the heading of the waypoint.
bool radius (float &radius) const
 Gets the radius of the waypoint.
local_position_t local_pos () const
 Gets the waypoint in local coordinates.

Protected Attributes

uint8_t frame_
 The reference frame of the waypoint.
uint16_t command_
 The MAV_CMD_NAV id of the waypoint.
uint8_t autocontinue_
 Flag to tell whether the vehicle should auto continue to the next waypoint once it reaches the current waypoint.
float param1_
 Parameter depending on the MAV_CMD_NAV id.
float param2_
 Parameter depending on the MAV_CMD_NAV id.
float param3_
 Parameter depending on the MAV_CMD_NAV id.
float param4_
 Parameter depending on the MAV_CMD_NAV id.
float param5_
 Parameter depending on the MAV_CMD_NAV id.
float param6_
 Parameter depending on the MAV_CMD_NAV id.
float param7_
 Parameter depending on the MAV_CMD_NAV id.

Constructor & Destructor Documentation

Waypoint::Waypoint ( mavlink_mission_item_t &  packet)

Initialize the waypoint handler.

Parameters:
packetThe received packet for creating a waypoint
Waypoint::Waypoint ( uint8_t  frame,
uint16_t  command,
uint8_t  autocontinue,
float  param1,
float  param2,
float  param3,
float  param4,
float  param5,
float  param6,
float  param7 
)

Initialize the waypoint handler.

Parameters:
frameThe reference frame of the waypoint
commandThe MAV_CMD_NAV id of the waypoint
autocontinueFlag to tell whether the vehicle should auto continue to the next waypoint once it reaches the current waypoint
param1Parameter depending on the MAV_CMD_NAV id
param2Parameter depending on the MAV_CMD_NAV id
param3Parameter depending on the MAV_CMD_NAV id
param4Parameter depending on the MAV_CMD_NAV id
param5Parameter depending on the MAV_CMD_NAV id (usually x/latitude)
param6Parameter depending on the MAV_CMD_NAV id (usually y/longitude)
param7Parameter depending on the MAV_CMD_NAV id (usually z/altitude)

Member Function Documentation

uint8_t Waypoint::autocontinue ( ) const

Gets the autocontinue state of the waypoint.

Returns:
autocontinue

Here is the caller graph for this function:

uint16_t Waypoint::command ( void  ) const

Gets the command of the waypoint.

Returns:
command

Here is the caller graph for this function:

uint8_t Waypoint::frame ( ) const

Gets the frame of the waypoint.

Returns:
frame
bool Waypoint::heading ( float &  heading) const

Gets the heading of the waypoint.

Outputs 0 if unsuccessful

Parameters:
headingOutput: heading
Returns:
Success

Here is the caller graph for this function:

local_position_t Waypoint::local_pos ( ) const

Gets the waypoint in local coordinates.

Returns:
Local waypoint position

Here is the call graph for this function:

Here is the caller graph for this function:

float Waypoint::param1 ( ) const

Gets param1 of the waypoint.

Returns:
param1

Here is the caller graph for this function:

float Waypoint::param2 ( ) const

Gets param2 of the waypoint.

Returns:
param2

Here is the caller graph for this function:

float Waypoint::param3 ( ) const

Gets param3 of the waypoint.

Returns:
param3
float Waypoint::param4 ( ) const

Gets param4 of the waypoint.

Returns:
param4
float Waypoint::param5 ( ) const

Gets param5 of the waypoint.

Returns:
param5
float Waypoint::param6 ( ) const

Gets param6 of the waypoint.

Returns:
param6
float Waypoint::param7 ( ) const

Gets param7 of the waypoint.

Returns:
param7
bool Waypoint::radius ( float &  radius) const

Gets the radius of the waypoint.

Outputs 0 if unsuccessful

Parameters:
radiusOutput: radius
Returns:
Success

Here is the caller graph for this function:

void Waypoint::send ( const Mavlink_stream mavlink_stream,
uint32_t  sysid,
const mavlink_message_t *  msg,
uint16_t  seq,
uint8_t  current 
)

Sends a given waypoint via a MAVLink message.

Parameters:
mavlink_streamThe mavlink stream to send the message through
sysidThe system ID
msgThe pointer to the received MAVLink message structure asking for a waypoint
seqThe sequence number of the packet
currentStates if the waypoint is the current waypoint (If is the waypoint we are heading towards and are current en route to waypoint)

Here is the call graph for this function:


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines