VSM C++ SDK
Vehicle Specific Modules SDK
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
move_action.h
Go to the documentation of this file.
1 // Copyright (c) 2018, Smart Projects Holdings Ltd
2 // All rights reserved.
3 // See LICENSE file for license details.
4 
10 #ifndef _UGCS_VSM_MOVE_ACTION_H_
11 #define _UGCS_VSM_MOVE_ACTION_H_
12 
13 #include <ugcs/vsm/action.h>
14 #include <ugcs/vsm/coordinates.h>
15 #include <ugcs/vsm/mavlink.h>
16 #include <ugcs/vsm/optional.h>
17 #include <ugcs/vsm/property.h>
18 
19 namespace ugcs {
20 namespace vsm {
21 
23 class Move_action: public Action {
25 
26 public:
30  typedef enum {
31  TURN_TYPE_STOP_AND_TURN = 0,
32  TURN_TYPE_STRAIGHT = 1,
33  TURN_TYPE_SPLINE = 2,
34  TURN_TYPE_BANK_TURN = 3,
35  } Turn_type;
36 
39  double loiter_orbit, double heading, double elevation) :
40  Action(Type::MOVE),
41  position(position),
42  wait_time(wait_time),
43  acceptance_radius(acceptance_radius),
44  loiter_orbit(loiter_orbit),
45  heading(heading),
46  elevation(elevation),
47  turn_type(TURN_TYPE_STRAIGHT)
48  {}
49 
54  Action(Type::MOVE),
55  position(Geodetic_tuple(0, 0, 0))
56  {
57  double lat = 0, lon = 0, alt = 0;
58  auto pi = p.find("latitude");
59  if (pi != p.end()) {
60  pi->second->Get_value(lat);
61  }
62  pi = p.find("longitude");
63  if (pi != p.end()) {
64  pi->second->Get_value(lon);
65  }
66  pi = p.find("altitude_amsl");
67  if (pi != p.end()) {
68  pi->second->Get_value(alt);
69  }
70  position = Geodetic_tuple(lat, lon, alt);
71  p.at("acceptance_radius")->Get_value(acceptance_radius);
72  p.at("heading")->Get_value(heading);
73  p.at("loiter_radius")->Get_value(loiter_orbit);
74  p.at("wait_time")->Get_value(wait_time);
75  p.at("ground_elevation")->Get_value(elevation);
76  int t;
77  p.at("turn_type")->Get_value(t);
78  turn_type = static_cast<Turn_type>(t);
79  }
80 
85 
90  double wait_time = 0;
91 
97  double acceptance_radius = 0;
98 
104  double loiter_orbit = 0;
105 
109  double heading = 0;
110 
114  double elevation = 0;
115 
116  Turn_type turn_type;
117 };
118 
120 template<>
121 struct Action::Mapper<Action::Type::MOVE> {
123  typedef Move_action type;
124 };
125 
126 } /* namespace vsm */
127 } /* namespace ugcs */
128 
129 #endif /* _UGCS_VSM_MOVE_ACTION_H_ */
Definition: property.h:250
double elevation
Elevation in meters (i.e.
Definition: move_action.h:114
Move_action type
Real type.
Definition: move_action.h:123
Coordinates tuple for geodetic CS.
Definition: coordinates.h:36
Type
Types of vehicle actions as part of task (mission).
Definition: action.h:30
double heading
Heading in radians.
Definition: move_action.h:109
Generic action.
Definition: action.h:22
Move_action(const Property_list &p)
Construct move action from protobuf command.
Definition: move_action.h:53
Generic action.
Map Action type enum value to specific Action type class.
Definition: action.h:120
Turn_type
Turn type at waypoint.
Definition: move_action.h:30
Move_action(Wgs84_position position, double wait_time, double acceptance_radius, double loiter_orbit, double heading, double elevation)
Construct move action explicitly.
Definition: move_action.h:38
Move vehicle to the specific position (waypoint).
Definition: move_action.h:23
double loiter_orbit
Radius of the point fly-by orbit in meters.
Definition: move_action.h:104
double acceptance_radius
Acceptance radius of the target position in meters.
Definition: move_action.h:97
double wait_time
Wait interval in seconds.
Definition: move_action.h:90
Wgs84_position position
Target global position of the movement.
Definition: move_action.h:84
#define DEFINE_COMMON_CLASS(__class_name,...)
Use this macro to define some common attributes for a class.
Definition: utils.h:25
Coordinates manipulation.