VSM C++ SDK
Vehicle Specific Modules SDK
vehicle_command.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 
10 #ifndef _VEHICLE_COMMAND_H_
11 #define _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  VIDEO_TOGGLE, // Toggle video recording on/off. Used for cameras which do not support separate commands for video start/stop.
30  UNKNOWN
31  };
32 
34  enum class Camera_power_state {
35  ON,
36  OFF,
37  TOGGLE, // Toggle the power state. Used for cameras which do not support separate commands for on and off.
38  UNKNOWN
39  };
40 
42  enum class Type {
44  ARM,
46  DISARM,
48  AUTO_MODE,
50  MANUAL_MODE,
52  GUIDED_MODE,
54  JOYSTICK_CONTROL_MODE,
56  RETURN_HOME,
58  TAKEOFF,
60  LAND,
62  EMERGENCY_LAND,
64  CAMERA_TRIGGER,
66  WAYPOINT,
68  PAUSE_MISSION,
70  RESUME_MISSION,
72  DIRECT_VEHICLE_CONTROL,
74  DIRECT_PAYLOAD_CONTROL,
76  CAMERA_POWER,
78  CAMERA_VIDEO_SOURCE,
79  };
80 
81  // Construct from argument list.
82  Vehicle_command(Type type, const Property_list& params);
83 
85  Vehicle_command(Type type, const mavlink::ugcs::Pld_command_long_ex& cmd);
86 
88  Type
89  Get_type() const
90  {
91  return type;
92  }
93 
94  // meters
95  float
96  Get_acceptance_radius() const
97  {
98  return acceptance_radius;
99  }
100 
101  // m/s
102  float
103  Get_speed() const
104  {
105  return speed;
106  }
107 
108  // clockwise radians from North
109  float
110  Get_heading() const
111  {
112  return heading;
113  }
114 
115  // Takeoff altitude AMSL.
116  float
117  Get_takeoff_altitude() const
118  {
119  return takeoff_altitude;
120  }
121 
122  // WP latitude.
123  float
124  Get_latitude() const
125  {
126  return position.Get_geodetic().latitude;
127  }
128 
129  // WP longitude.
130  float
131  Get_longitude() const
132  {
133  return position.Get_geodetic().longitude;
134  }
135 
136  // WP altitude AMSL.
137  float
138  Get_altitude() const
139  {
140  return position.Get_geodetic().altitude;
141  }
142 
143  // ADSB flight number
144  std::string
145  Get_adsb_flight_id() const
146  {
147  return string1;
148  }
149 
150  // ADSB registration number
151  std::string
152  Get_adsb_registration() const
153  {
154  return string1;
155  }
156 
157  uint32_t
158  Get_adsb_icao_code() const
159  {
160  return integer1;
161  }
162 
164  Get_adsb_operating_mode() const
165  {
166  return integer1;
167  }
168 
170  Get_adsb_ident_on() const
171  {
172  return integer2;
173  }
174 
176  Get_adsb_squawk() const
177  {
178  return integer3;
179  }
180 
181  float
182  Get_pitch() const
183  {
184  return pitch;
185  }
186 
187  float
188  Get_roll() const
189  {
190  return roll;
191  }
192 
193  float
194  Get_yaw() const
195  {
196  return yaw;
197  }
198 
199  float
200  Get_throttle() const
201  {
202  return throttle;
203  }
204 
205  float
206  Get_zoom() const
207  {
208  return zoom;
209  }
210 
211  int
212  Get_payload_id() const
213  {
214  return payload_id;
215  }
216 
217 private:
218 
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 /* _VEHICLE_COMMAND_H_ */
UGCS root namespace.
Definition: android-linux/ugcs/vsm/platform_sockets.h:27
Definition: property.h:191
Camera_power_state
Camera power state.
Definition: vehicle_command.h:34
Camera_trigger_state
Camera trigger state.
Definition: vehicle_command.h:25
Type Get_type() const
Get type of the command.
Definition: vehicle_command.h:89
Information about a command for a vehicle.
Definition: vehicle_command.h:22
Type
Type of the command.
Definition: vehicle_command.h:42
Coordinates manipulation.