VSM C++ SDK
Vehicle Specific Modules SDK
ugcs::vsm::Move_action Class Reference

Move vehicle to the specific position (waypoint). More...

#include <move_action.h>

Inheritance diagram for ugcs::vsm::Move_action:
ugcs::vsm::Action

Public Types

enum  Turn_type { TURN_TYPE_STOP_AND_TURN = 0, TURN_TYPE_STRAIGHT = 1, TURN_TYPE_SPLINE = 2, TURN_TYPE_BANK_TURN = 3 }
 Turn type at waypoint.
 
typedef std::shared_ptr< Move_actionPtr
 Pointer type.
 
typedef std::weak_ptr< Move_actionWeak_ptr
 Pointer type.
 
- Public Types inherited from ugcs::vsm::Action
enum  Type {
  Type::MOVE, Type::WAIT, Type::PAYLOAD_STEERING, Type::TAKEOFF,
  Type::LANDING, Type::CHANGE_SPEED, Type::SET_HOME, Type::POI,
  Type::HEADING, Type::CAMERA_CONTROL, Type::CAMERA_TRIGGER, Type::PANORAMA,
  Type::TASK_ATTRIBUTES, Type::CAMERA_SERIES_BY_TIME, Type::CAMERA_SERIES_BY_DISTANCE, Type::SET_PARAMETER,
  Type::SET_SERVO, Type::REPEAT_SERVO
}
 Types of vehicle actions as part of task (mission). More...
 
typedef std::shared_ptr< ActionPtr
 Pointer type.
 
typedef std::weak_ptr< ActionWeak_ptr
 Pointer type.
 
typedef ugcs::vsm::Param_exception< Format_exception_dummy_struct,> Format_exception
 

Public Member Functions

 Move_action (Wgs84_position position, double wait_time, double acceptance_radius, double loiter_orbit, double heading, double elevation)
 Construct move action explicitly. More...
 
 Move_action (const mavlink::ugcs::Pld_mission_item_ex &item, Optional< double > &takeoff_altitude)
 Construct move action from Mavlink extended mission item. More...
 
 Move_action (const Property_list &p)
 Construct move action from protobuf command.
 
- Public Member Functions inherited from ugcs::vsm::Action
 Action (Type type)
 Construct action of specific type. More...
 
virtual ~Action ()
 Make sure Action is polymorphic. More...
 
Type Get_type () const
 Get action type. More...
 
void Set_id (int id)
 
std::string Get_name ()
 Get human readable name of the action. More...
 
template<Type type_val>
Mapper< type_val >::type::Ptr Get_action ()
 Get pointer to specific action as determined by Get_type. More...
 

Static Public Member Functions

template<typename... Args>
static Ptr Create (Args &&...args)
 Create an instance. More...
 
- Static Public Member Functions inherited from ugcs::vsm::Action
template<typename... Args>
static Ptr Create (Args &&...args)
 Create an instance. More...
 

Public Attributes

Wgs84_position position
 Target global position of the movement.
 
double wait_time = 0
 Wait interval in seconds. More...
 
double acceptance_radius = 0
 Acceptance radius of the target position in meters. More...
 
double loiter_orbit = 0
 Radius of the point fly-by orbit in meters. More...
 
double heading = 0
 Heading in radians.
 
double elevation = 0
 Elevation in meters (i.e. More...
 
Turn_type turn_type
 
- Public Attributes inherited from ugcs::vsm::Action
int command_id = -1
 

Detailed Description

Move vehicle to the specific position (waypoint).

Constructor & Destructor Documentation

ugcs::vsm::Move_action::Move_action ( Wgs84_position  position,
double  wait_time,
double  acceptance_radius,
double  loiter_orbit,
double  heading,
double  elevation 
)
inline

Construct move action explicitly.

ugcs::vsm::Move_action::Move_action ( const mavlink::ugcs::Pld_mission_item_ex &  item,
Optional< double > &  takeoff_altitude 
)
inline

Construct move action from Mavlink extended mission item.

Parameters
itemWith command equal to mavlink::MAV_CMD::MAV_CMD_NAV_WAYPOINT

Member Function Documentation

template<typename... Args>
static Ptr ugcs::vsm::Move_action::Create ( Args &&...  args)
inlinestatic

Create an instance.

Member Data Documentation

double ugcs::vsm::Move_action::acceptance_radius = 0

Acceptance radius of the target position in meters.

When the sphere with the radius centered at the target position is hit by the vehicle the target position is considered reached.

double ugcs::vsm::Move_action::elevation = 0

Elevation in meters (i.e.

terrain height) underneath the position.

double ugcs::vsm::Move_action::loiter_orbit = 0

Radius of the point fly-by orbit in meters.

Positive value stands for the CW direction, negative - CCW. Use

0

for no-braking pass through the target point.

double ugcs::vsm::Move_action::wait_time = 0

Wait interval in seconds.

Shows how long the vehicle should stay/hold at the target position.


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