VSM C++ SDK
Vehicle Specific Modules SDK
landing_action.h
Go to the documentation of this file.
1 // Copyright (c) 2014, Smart Projects Holdings Ltd
2 // All rights reserved.
3 // See LICENSE file for license details.
4 
9 #ifndef _LANDING_ACTION_H_
10 #define _LANDING_ACTION_H_
11 
12 #include <ugcs/vsm/action.h>
13 #include <ugcs/vsm/coordinates.h>
14 #include <ugcs/vsm/mavlink.h>
15 
16 namespace ugcs {
17 namespace vsm {
18 
20 class Landing_action: public Action {
22 
23 public:
24 
27  double descend_rate, double acceptance_radius) :
28  Action(Type::LANDING),
29  position(position),
30  heading(heading),
31  elevation(elevation),
32  descend_rate(descend_rate),
34 
40  Landing_action(const mavlink::ugcs::Pld_mission_item_ex& item) :
41  Action(Type::LANDING),
42  position(Geodetic_tuple(item->x * M_PI / 180.0,
43  item->y * M_PI / 180.0,
44  item->z)),
45  heading(item->param4 * M_PI / 180.0),
46  elevation(item->elevation),
47  descend_rate(item->param3),
48  acceptance_radius(item->param2)
49  {
50  ASSERT(item->command == mavlink::ugcs::MAV_CMD::MAV_CMD_NAV_LAND_EX);
51  }
52 
57  Action(Type::LANDING),
58  position(Geodetic_tuple(0,0,0))
59  {
60  double lat = 0, lon = 0, alt = 0;
61  auto pi = p.find("latitude");
62  if (pi != p.end()) {
63  pi->second->Get_value(lat);
64  }
65  pi = p.find("longitude");
66  if (pi != p.end()) {
67  pi->second->Get_value(lon);
68  }
69  pi = p.find("altitude_amsl");
70  if (pi != p.end()) {
71  pi->second->Get_value(alt);
72  }
73  position = Geodetic_tuple(lat, lon, alt);
74  p.at("acceptance_radius")->Get_value(acceptance_radius);
75  p.at("heading")->Get_value(heading);
76  p.at("descent_rate")->Get_value(descend_rate);
77  p.at("ground_elevation")->Get_value(elevation);
78  }
79 
83 
85  double heading;
86 
90  double elevation;
91 
93  double descend_rate;
94 
98 };
99 
101 template<>
105 };
106 
107 } /* namespace vsm */
108 } /* namespace ugcs */
109 
110 #endif /* _LANDING_ACTION_H_ */
UGCS root namespace.
Definition: android-linux/ugcs/vsm/platform_sockets.h:27
Landing_action type
Real type.
Definition: landing_action.h:104
Definition: property.h:191
double elevation
Elevation in meters (i.e.
Definition: landing_action.h:90
Coordinates tuple for geodetic CS.
Definition: coordinates.h:41
Type
Types of vehicle actions as part of task (mission).
Definition: action.h:30
Generic action.
Definition: action.h:22
Wgs84_position position
Landing position.
Definition: landing_action.h:82
#define ASSERT(x)
No action in release.
Definition: debug.h:68
double heading
Heading in radians.
Definition: landing_action.h:85
Generic action.
Map Action type enum value to specific Action type class.
Definition: action.h:117
double descend_rate
Descending rate, m/s.
Definition: landing_action.h:93
Land at the specified position.
Definition: landing_action.h:20
Landing_action(const Property_list &p)
Construct move action from protobuf command.
Definition: landing_action.h:56
double acceptance_radius
Acceptance radius of the position.
Definition: landing_action.h:97
Landing_action(const mavlink::ugcs::Pld_mission_item_ex &item)
Construct landing action from Mavlink extended mission item.
Definition: landing_action.h:40
#define M_PI
PI constant.
Definition: coordinates.h:21
#define DEFINE_COMMON_CLASS(__class_name,...)
Use this macro to define some common attributes for a class.
Definition: utils.h:25
Coordinates manipulation.
Landing action ugcs::vsm::Landing_action.