VSM C++ SDK
Vehicle Specific Modules SDK
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
vehicle_command.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_VEHICLE_COMMAND_H_
11 #define _UGCS_VSM_VEHICLE_COMMAND_H_
12 
13 #include <ugcs/vsm/mavlink.h>
14 #include <ugcs/vsm/coordinates.h>
15 #include <ugcs/vsm/property.h>
16 
17 
18 namespace ugcs {
19 namespace vsm {
20 
23 public:
25  enum class Camera_trigger_state {
26  SINGLE_SHOT,
27  VIDEO_START,
28  VIDEO_STOP,
29  // Toggle video recording on/off.
30  // Used for cameras which do not support separate commands for video start/stop.
31  VIDEO_TOGGLE,
32  UNKNOWN
33  };
34 
36  enum class Camera_power_state {
37  ON,
38  OFF,
39  // Toggle the power state.
40  // Used for cameras which do not support separate commands for on and off.
41  TOGGLE,
42  UNKNOWN
43  };
44 
46  enum class Type {
48  ARM,
50  DISARM,
52  AUTO_MODE,
62  TAKEOFF,
64  LAND,
70  WAYPOINT,
83  };
84 
85  // Construct from argument list.
86  Vehicle_command(Type type, const Property_list& params);
87 
89  Type
90  Get_type() const
91  {
92  return type;
93  }
94 
95  // meters
96  float
97  Get_acceptance_radius() const
98  {
99  return acceptance_radius;
100  }
101 
102  // m/s
103  float
104  Get_speed() const
105  {
106  return speed;
107  }
108 
109  // clockwise radians from North
110  float
111  Get_heading() const
112  {
113  return heading;
114  }
115 
116  // Takeoff altitude AMSL.
117  float
118  Get_takeoff_altitude() const
119  {
120  return takeoff_altitude;
121  }
122 
123  // WP latitude.
124  float
125  Get_latitude() const
126  {
127  return position.Get_geodetic().latitude;
128  }
129 
130  // WP longitude.
131  float
132  Get_longitude() const
133  {
134  return position.Get_geodetic().longitude;
135  }
136 
137  // WP altitude AMSL.
138  float
139  Get_altitude() const
140  {
141  return position.Get_geodetic().altitude;
142  }
143 
144  // ADSB flight number
145  std::string
146  Get_adsb_flight_id() const
147  {
148  return string1;
149  }
150 
151  // ADSB registration number
152  std::string
153  Get_adsb_registration() const
154  {
155  return string1;
156  }
157 
158  uint32_t
159  Get_adsb_icao_code() const
160  {
161  return integer1;
162  }
163 
164  mavlink::Int32
165  Get_adsb_operating_mode() const
166  {
167  return integer1;
168  }
169 
170  mavlink::Int32
171  Get_adsb_ident_on() const
172  {
173  return integer2;
174  }
175 
176  mavlink::Int32
177  Get_adsb_squawk() const
178  {
179  return integer3;
180  }
181 
182  float
183  Get_pitch() const
184  {
185  return pitch;
186  }
187 
188  float
189  Get_roll() const
190  {
191  return roll;
192  }
193 
194  float
195  Get_yaw() const
196  {
197  return yaw;
198  }
199 
200  float
201  Get_throttle() const
202  {
203  return throttle;
204  }
205 
206  float
207  Get_zoom() const
208  {
209  return zoom;
210  }
211 
212  int
213  Get_payload_id() const
214  {
215  return payload_id;
216  }
217 
218 private:
220  Type type;
221 
222  Wgs84_position position;
223 
229  float acceptance_radius;
230 
234  float speed;
235 
237  float heading;
238 
240  float vertical_speed = 0;
241 
243  float roll;
245  float pitch;
247  float yaw;
249  float throttle;
251  float zoom;
252 
254  float takeoff_altitude;
255 
257  int payload_id; // DEPRECATED
258 
259  Camera_power_state power_state;
260  Camera_trigger_state trigger_state;
261 
262  std::string string1;
263 
264  mavlink::Int32 integer1;
265  mavlink::Int32 integer2;
266  mavlink::Int32 integer3;
267 };
268 
269 } /* namespace vsm */
270 } /* namespace ugcs */
271 
272 #endif /* _UGCS_VSM_VEHICLE_COMMAND_H_ */
Definition: property.h:250
Camera_power_state
Camera power state.
Definition: vehicle_command.h:36
Position< Wgs84_datum > Wgs84_position
Position defined in WGS84 geodetic system.
Definition: coordinates.h:308
Camera_trigger_state
Camera trigger state.
Definition: vehicle_command.h:25
Trigger the camera, take snapshot.
Type Get_type() const
Get type of the command.
Definition: vehicle_command.h:90
double latitude
Latitude value, radians.
Definition: coordinates.h:39
double longitude
Longitude value, radians.
Definition: coordinates.h:39
Information about a command for a vehicle.
Definition: vehicle_command.h:22
Geodetic_tuple Get_geodetic() const
Get representation in geodetic coordinates.
Definition: coordinates.h:90
Type
Type of the command.
Definition: vehicle_command.h:46
Coordinates manipulation.
double altitude
Altitude value, meters.
Definition: coordinates.h:39