mavsdk::MissionItem Class Reference

#include: mission_item.h


A mission is a vector of MissionItems.

Each MissionItem can contain a position and/or actions. Mission items are just building blocks to assemble a mission, which can be sent to (or received from) a system. They cannot be used independently.

Public Types

Type Description
enum CameraAction Possible camera actions at a mission item.

Public Member Functions

Type Name Description
  MissionItem () Constructor (internal use only).
  ~MissionItem () Destructor (internal use only).
  MissionItem (const MissionItem &)=delete Copy constructor (object is not copyable).
void set_position (double latitude_deg, double longitude_deg) Set the position of a mission item.
void set_relative_altitude (float altitude_m) Set the relative altitude of a mission item.
void set_fly_through (bool fly_through) Set the fly-through property of a mission item.
void set_acceptance_radius (float radius_m) Set the acceptance radius property of a mission item.
void set_speed (float speed_m_s) Set the speed to use after a mission item.
void set_gimbal_pitch_and_yaw (float pitch_deg, float yaw_deg) Set the pitch and yaw angle of a gimbal at that mission item.
void set_loiter_time (float loiter_time_s) Set loiter time in seconds.
void set_camera_action (CameraAction action) Set the camera action for a mission item.
void set_camera_photo_interval (double interval_s) Set the camera photo interval.
double get_latitude_deg () const Get the latitude of a mission item.
double get_longitude_deg () const Get the longitude of a mission item.
bool has_position_set () const Reports whether position info (Lat, Lon) was set for this mission item.
float get_relative_altitude_m () const Get the relative altitude of a mission item.
bool get_fly_through () const Get the fly-through property of a mission item.
float get_acceptance_radius_m () const Get the acceptance radius of a mission item.
float get_speed_m_s () const Get the speed to be used after this mission item.
float get_gimbal_pitch_deg () const Get the gimbal pitch of a mission item.
float get_gimbal_yaw_deg () const Get the gimbal yaw of a mission item.
float get_loiter_time_s () const Get loiter time in seconds.
CameraAction get_camera_action () const Get the camera action set for this mission item.
double get_camera_photo_interval_s () const Get the camera photo interval that was set for this mission item.
const MissionItem & operator= (const MissionItem &)=delete Equality operator (object is not copyable).

Static Public Member Functions

Type Name Description
std::string to_str (CameraAction camera_action) Converts CameraAction to English strings.

Constructor & Destructor Documentation

MissionItem()

mavsdk::MissionItem::MissionItem()

Constructor (internal use only).

~MissionItem()

mavsdk::MissionItem::~MissionItem()

Destructor (internal use only).

MissionItem()

mavsdk::MissionItem::MissionItem(const MissionItem &)=delete

Copy constructor (object is not copyable).

Parameters

Member Enumeration Documentation

enum CameraAction

Possible camera actions at a mission item.

Value Description
TAKE_PHOTO Take single photo.
START_PHOTO_INTERVAL Start capturing photos at regular intervals - see set_camera_photo_interval().
STOP_PHOTO_INTERVAL Stop capturing photos at regular intervals.
START_VIDEO Start capturing video.
STOP_VIDEO Stop capturing video.
NONE No action.

See Also:

Member Function Documentation

set_position()

void mavsdk::MissionItem::set_position(double latitude_deg, double longitude_deg)

Set the position of a mission item.

Parameters

  • double latitude_deg - Latitude of the waypoint in degrees.
  • double longitude_deg - Longitude of the waypoint in degrees.

set_relative_altitude()

void mavsdk::MissionItem::set_relative_altitude(float altitude_m)

Set the relative altitude of a mission item.

Parameters

  • float altitude_m - Altitude relative to takeoff position in metres.

set_fly_through()

void mavsdk::MissionItem::set_fly_through(bool fly_through)

Set the fly-through property of a mission item.

Parameters

  • bool fly_through - If true the drone will fly through the waypoint without stopping. If false the drone will come to a stop at the waypoint before continuing.

set_acceptance_radius()

void mavsdk::MissionItem::set_acceptance_radius(float radius_m)

Set the acceptance radius property of a mission item.

Parameters

  • float radius_m - Radius in meters around the mission_item where it will be considered as reached.

set_speed()

void mavsdk::MissionItem::set_speed(float speed_m_s)

Set the speed to use after a mission item.

Parameters

  • float speed_m_s - Speed to use after this mission item in metres/second.

set_gimbal_pitch_and_yaw()

void mavsdk::MissionItem::set_gimbal_pitch_and_yaw(float pitch_deg, float yaw_deg)

Set the pitch and yaw angle of a gimbal at that mission item.

Parameters

  • float pitch_deg - The new pitch angle of the gimbal in degrees (0: horizontal, positive up, -90: vertical downward facing).
  • float yaw_deg - The new yaw angle of the gimbal in degrees (0: forward, positive clock-wise, 90: to the right).

set_loiter_time()

void mavsdk::MissionItem::set_loiter_time(float loiter_time_s)

Set loiter time in seconds.

This specifies the delay at a waypoint before executing next mission item. It can be used to wait for vehicle to slow down or a gimbal to arrive at the set orientation.

Parameters

  • float loiter_time_s - The time to wait (loiter), in seconds.

set_camera_action()

void mavsdk::MissionItem::set_camera_action(CameraAction action)

Set the camera action for a mission item.

Parameters

set_camera_photo_interval()

void mavsdk::MissionItem::set_camera_photo_interval(double interval_s)

Set the camera photo interval.

This only has an effect if used together with CameraAction::START_PHOTO_INTERVAL.

Parameters

  • double interval_s - Interval between photo captures in seconds.

get_latitude_deg()

double mavsdk::MissionItem::get_latitude_deg() const

Get the latitude of a mission item.

Returns

 double - Latitude in degrees.

get_longitude_deg()

double mavsdk::MissionItem::get_longitude_deg() const

Get the longitude of a mission item.

Returns

 double - Longitude in degrees.

has_position_set()

bool mavsdk::MissionItem::has_position_set() const

Reports whether position info (Lat, Lon) was set for this mission item.

Returns

 bool - true if Lat, Lon is set for this mission item.

get_relative_altitude_m()

float mavsdk::MissionItem::get_relative_altitude_m() const

Get the relative altitude of a mission item.

Returns

 float - The altitude relative to the takeoff position in metres.

get_fly_through()

bool mavsdk::MissionItem::get_fly_through() const

Get the fly-through property of a mission item.

Returns

 bool - true if the drone will fly through the waypoint without stopping. false if the drone will come to a stop at the waypoint before continuing.

get_acceptance_radius_m()

float mavsdk::MissionItem::get_acceptance_radius_m() const

Get the acceptance radius of a mission item.

Returns

 float - Acceptance radius in meters.

get_speed_m_s()

float mavsdk::MissionItem::get_speed_m_s() const

Get the speed to be used after this mission item.

Returns

 float - Speed in metres/second.

get_gimbal_pitch_deg()

float mavsdk::MissionItem::get_gimbal_pitch_deg() const

Get the gimbal pitch of a mission item.

Returns

 float - Gimbal pitch in degrees.

get_gimbal_yaw_deg()

float mavsdk::MissionItem::get_gimbal_yaw_deg() const

Get the gimbal yaw of a mission item.

Returns

 float - Gimbal yaw in degrees.

get_loiter_time_s()

float mavsdk::MissionItem::get_loiter_time_s() const

Get loiter time in seconds.

Returns

 float - Loiter time in seconds.

get_camera_action()

CameraAction mavsdk::MissionItem::get_camera_action() const

Get the camera action set for this mission item.

Returns

CameraAction - Camera action enum value.

get_camera_photo_interval_s()

double mavsdk::MissionItem::get_camera_photo_interval_s() const

Get the camera photo interval that was set for this mission item.

This only has an effect if used together with CameraAction::START_PHOTO_INTERVAL.

Returns

 double - Camera photo interval in seconds.

operator=()

const MissionItem& mavsdk::MissionItem::operator=(const MissionItem &)=delete

Equality operator (object is not copyable).

Parameters

Returns

 const MissionItem & -

to_str()

static std::string mavsdk::MissionItem::to_str(CameraAction camera_action)

Converts CameraAction to English strings.

Parameters

Returns

 std::string - Human readable english string for CameraAction.

© Dronecode 2017-2019. License: CC BY 4.0            Updated: 2019-11-05 22:27:07

results matching ""

    No results matching ""