VSM C++ SDK
Vehicle Specific Modules SDK
vehicle.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 
11 #ifndef VEHICLE_H_
12 #define VEHICLE_H_
13 
16 #include <ugcs/vsm/mavlink.h>
17 #include <ugcs/vsm/enum_set.h>
18 #include <ugcs/vsm/device.h>
19 #include <ugcs/vsm/crc32.h>
20 
21 #include <stdint.h>
22 #include <memory>
23 #include <unordered_map>
24 
25 namespace ugcs {
26 namespace vsm {
27 
28 static const std::string legacy_commands[] = {std::string("")};
29 
35 class Vehicle: public Device {
37 public:
38 
39  // @{
42  enum class Capability {
43  ARM_AVAILABLE,
44  DISARM_AVAILABLE,
45  AUTO_MODE_AVAILABLE,
46  MANUAL_MODE_AVAILABLE,
47  RETURN_HOME_AVAILABLE,
48  TAKEOFF_AVAILABLE,
49  LAND_AVAILABLE,
50  EMERGENCY_LAND_AVAILABLE,
51  CAMERA_TRIGGER_AVAILABLE,
52  WAYPOINT_AVAILABLE,
53  PAUSE_MISSION_AVAILABLE,
54  RESUME_MISSION_AVAILABLE,
55  GUIDED_MODE_AVAILABLE,
56  JOYSTICK_MODE_AVAILABLE,
57  PAYLOAD_POWER_AVAILABLE,
58  SWITCH_VIDEO_SOURCE_AVAILABLE,
59  DIRECT_VEHICLE_CONTROL_AVAILABLE,
60  DIRECT_PAYLOAD_CONTROL_AVAILABLE,
61  LAST
62  };
63  // @}
64 
65  // @{
68  enum class Capability_state {
69  ARM_ENABLED,
70  DISARM_ENABLED,
71  AUTO_MODE_ENABLED,
72  MANUAL_MODE_ENABLED,
73  RETURN_HOME_ENABLED,
74  TAKEOFF_ENABLED,
75  LAND_ENABLED,
76  EMERGENCY_LAND_ENABLED,
77  CAMERA_TRIGGER_ENABLED,
78  WAYPOINT_ENABLED,
79  PAUSE_MISSION_ENABLED,
80  RESUME_MISSION_ENABLED,
81  GUIDED_MODE_ENABLED,
82  JOYSTICK_MODE_ENABLED,
83  PAYLOAD_POWER_ENABLED,
84  SWITCH_VIDEO_SOURCE_ENABLED,
85  DIRECT_VEHICLE_CONTROL_ENABLED,
86  DIRECT_PAYLOAD_CONTROL_ENABLED,
87  LAST
88  };
89  // @}
90 
93 
96 
118  Vehicle(mavlink::MAV_TYPE type, mavlink::MAV_AUTOPILOT autopilot,
119  const Capabilities& capabilities,
120  const std::string& serial_number,
121  const std::string& model_name,
122  int model_name_is_hardcoded = false,
123  bool create_thread = true);
124 
126  virtual
127  ~Vehicle() {};
128 
130  Vehicle(const Vehicle &) = delete;
131 
137  void
139 
141  const std::string&
142  Get_serial_number() const;
143 
145  const std::string&
146  Get_model_name() const;
147 
149  const std::string&
150  Get_port_name() const;
151 
153  const std::string&
154  Get_autopilot_serial() const;
155 
156  ugcs::vsm::mavlink::MAV_AUTOPILOT
157  Get_autopilot() const;
158 
159  const std::string&
160  Get_autopilot_type() const;
161 
164  class Hasher
165  {
166  public:
168  size_t
169  operator ()(const Vehicle::Ptr& ptr) const
170  {
171  return hasher(ptr.get());
172  }
173  private:
175  static std::hash<Vehicle*> hasher;
176  };
177 
178 protected:
179 
180  typedef enum {
181  SUBDEVICE_TYPE_FC = 1,
182  SUBDEVICE_TYPE_CAMERA = 2,
183  SUBDEVICE_TYPE_GIMBAL = 3,
184  SUBDEVICE_TYPE_ADSB_TRANSPONDER = 4,
185  } Subdevice_type;
186 
187  class Subdevice {
188  public:
189  Subdevice(Subdevice_type t):type(t){};
190  Subdevice_type type;
191  // Subdevice telemetry fields.
192  std::unordered_map<std::string, Property::Ptr> telemetry_fields;
193  // Commands supported by subdevice.
194  std::unordered_map<std::string, Vsm_command::Ptr> commands;
195  };
196 
198  const std::string serial_number;
199 
201  const std::string model_name;
202 
204  std::string port_name;
205 
207  std::string autopilot_serial;
208 
210  std::string autopilot_type;
211 
213  std::string frame_type;
214 
216  const mavlink::MAV_TYPE type; // Deprecated
217  ugcs::vsm::proto::Vehicle_type vehicle_type;
218 
219  std::vector<Subdevice> subdevices;
220 
222  typedef struct {
223  unsigned int fc;
224  unsigned int camera;
225  unsigned int gimbal;
226  unsigned int adsb_transponder;
227  } Subsystems;
228 
229  Subsystems subsystems;
230 
231  ugcs::vsm::Optional<ugcs::vsm::proto::Flight_mode> current_flight_mode;
232 
233  ugcs::vsm::Property::Ptr t_control_mode = nullptr;
234  ugcs::vsm::Property::Ptr t_is_armed = nullptr;
235  ugcs::vsm::Property::Ptr t_uplink_present = nullptr;
236  ugcs::vsm::Property::Ptr t_downlink_present = nullptr;
237  ugcs::vsm::Property::Ptr t_main_voltage = nullptr;
238  ugcs::vsm::Property::Ptr t_main_current = nullptr;
239  ugcs::vsm::Property::Ptr t_gcs_link_quality = nullptr;
240  ugcs::vsm::Property::Ptr t_rc_link_quality = nullptr;
241  ugcs::vsm::Property::Ptr t_latitude = nullptr;
242  ugcs::vsm::Property::Ptr t_longitude = nullptr;
243  ugcs::vsm::Property::Ptr t_altitude_raw = nullptr;
244  ugcs::vsm::Property::Ptr t_altitude_amsl = nullptr;
245  ugcs::vsm::Property::Ptr t_ground_speed = nullptr;
246  ugcs::vsm::Property::Ptr t_air_speed = nullptr;
247  ugcs::vsm::Property::Ptr t_course = nullptr;
248  ugcs::vsm::Property::Ptr t_vertical_speed = nullptr;
249  ugcs::vsm::Property::Ptr t_pitch = nullptr;
250  ugcs::vsm::Property::Ptr t_roll = nullptr;
251  ugcs::vsm::Property::Ptr t_heading = nullptr;
252  ugcs::vsm::Property::Ptr t_gps_fix = nullptr;
253  ugcs::vsm::Property::Ptr t_satellite_count = nullptr;
254  ugcs::vsm::Property::Ptr t_altitude_origin = nullptr;
255  ugcs::vsm::Property::Ptr t_home_altitude_amsl = nullptr;
256  ugcs::vsm::Property::Ptr t_home_altitude_raw = nullptr;
257  ugcs::vsm::Property::Ptr t_home_latitude = nullptr;
258  ugcs::vsm::Property::Ptr t_home_longitude = nullptr;
259  ugcs::vsm::Property::Ptr t_target_altitude_amsl = nullptr;
260  ugcs::vsm::Property::Ptr t_target_altitude_raw = nullptr;
261  ugcs::vsm::Property::Ptr t_target_latitude = nullptr;
262  ugcs::vsm::Property::Ptr t_target_longitude = nullptr;
263  ugcs::vsm::Property::Ptr t_current_command = nullptr;
264  ugcs::vsm::Property::Ptr t_current_mission_id = nullptr;
265  ugcs::vsm::Property::Ptr t_flight_mode = nullptr;
266  ugcs::vsm::Property::Ptr t_native_flight_mode = nullptr;
267  ugcs::vsm::Property::Ptr t_fence_enabled = nullptr;
268 
269  ugcs::vsm::Vsm_command::Ptr c_mission_upload = nullptr;
270  ugcs::vsm::Vsm_command::Ptr c_auto = nullptr;
271  ugcs::vsm::Vsm_command::Ptr c_arm = nullptr;
272  ugcs::vsm::Vsm_command::Ptr c_disarm = nullptr;
273  ugcs::vsm::Vsm_command::Ptr c_waypoint = nullptr;
274  ugcs::vsm::Vsm_command::Ptr c_guided = nullptr;
275  ugcs::vsm::Vsm_command::Ptr c_manual = nullptr;
276  ugcs::vsm::Vsm_command::Ptr c_pause = nullptr;
277  ugcs::vsm::Vsm_command::Ptr c_resume = nullptr;
278  ugcs::vsm::Vsm_command::Ptr c_rth = nullptr;
279  ugcs::vsm::Vsm_command::Ptr c_land_command = nullptr;
280  ugcs::vsm::Vsm_command::Ptr c_joystick = nullptr;
281  ugcs::vsm::Vsm_command::Ptr c_direct_vehicle_control = nullptr;
282  ugcs::vsm::Vsm_command::Ptr c_takeoff_command = nullptr;
283  ugcs::vsm::Vsm_command::Ptr c_emergency_land = nullptr;
284  ugcs::vsm::Vsm_command::Ptr c_camera_trigger_command = nullptr;
285  ugcs::vsm::Vsm_command::Ptr c_adsb_set_ident = nullptr;
286  ugcs::vsm::Vsm_command::Ptr c_adsb_set_mode = nullptr;
287  ugcs::vsm::Vsm_command::Ptr c_direct_payload_control = nullptr;
288  ugcs::vsm::Vsm_command::Ptr c_camera_power = nullptr;
289  ugcs::vsm::Vsm_command::Ptr c_camera_video_source = nullptr;
290  ugcs::vsm::Vsm_command::Ptr c_adsb_set_parameter = nullptr;
291  ugcs::vsm::Vsm_command::Ptr c_set_servo = nullptr;
292  ugcs::vsm::Vsm_command::Ptr c_repeat_servo = nullptr;
293  ugcs::vsm::Vsm_command::Ptr c_set_fence = nullptr;
294  ugcs::vsm::Vsm_command::Ptr c_trigger_calibration = nullptr;
295 
296  ugcs::vsm::Vsm_command::Ptr c_wait = nullptr;
297  ugcs::vsm::Vsm_command::Ptr c_move = nullptr;
298  ugcs::vsm::Vsm_command::Ptr c_set_speed = nullptr;
299  ugcs::vsm::Vsm_command::Ptr c_set_home = nullptr;
300  ugcs::vsm::Vsm_command::Ptr c_set_poi = nullptr;
301  ugcs::vsm::Vsm_command::Ptr c_set_heading = nullptr;
302  ugcs::vsm::Vsm_command::Ptr c_panorama = nullptr;
303  ugcs::vsm::Vsm_command::Ptr c_camera_trigger_mission = nullptr;
304  ugcs::vsm::Vsm_command::Ptr c_camera_by_time = nullptr;
305  ugcs::vsm::Vsm_command::Ptr c_camera_by_distance = nullptr;
306  ugcs::vsm::Vsm_command::Ptr c_land_mission = nullptr;
307  ugcs::vsm::Vsm_command::Ptr c_takeoff_mission = nullptr;
308  ugcs::vsm::Vsm_command::Ptr c_set_parameter = nullptr;
309  ugcs::vsm::Vsm_command::Ptr c_payload_control = nullptr;
310 
311  Property::Ptr p_rc_loss_action = nullptr;
312  Property::Ptr p_gps_loss_action = nullptr;
313  Property::Ptr p_low_battery_action = nullptr;
314  Property::Ptr p_wp_turn_type = nullptr;
315 
319  virtual void
321  {};
322 
326  virtual void
328  {};
329 
330  void
331  Set_rc_loss_actions(std::initializer_list<proto::Failsafe_action> actions);
332 
333  void
334  Set_gps_loss_actions(std::initializer_list<proto::Failsafe_action> actions);
335 
336  void
337  Set_low_battery_actions(std::initializer_list<proto::Failsafe_action> actions);
338 
345  void
347 
351  void
352  Set_altitude_origin(float altitude_amsl);
353 
354  /*
355  * Below are methods which are called by VSM SDK in vehicle context and
356  * should be overridden by user code.
357  */
358 
363  // Translates incoming message to old style Vehicle_request
364  virtual void
366  Ucs_request::Ptr ucs_request);
367 
368  // old style completion handler
369  void
370  Command_completed(
372  const std::string& status_text,
373  Ucs_request::Ptr ucs_request);
374 
375  void
376  Command_failed(
377  Ucs_request::Ptr ucs_request,
378  const std::string& status_text,
379  proto::Status_code code = ugcs::vsm::proto::STATUS_FAILED);
380 
381  void
382  Command_succeeded(
383  Ucs_request::Ptr ucs_request);
384 
388  virtual void
390 
394  virtual void
396 
397  // Used by Cucs_processor only.
398  // Derived class must override.
399  virtual void
400  Fill_register_msg(ugcs::vsm::proto::Vsm_message&);
401 
402  /* End of methods called by VSM SDK. */
403 
404  /* Below are methods which should be called by user code from derived
405  * vehicle class. */
406 
408  class Sys_status {
409  public:
410 
412  enum class Control_mode {
414  MANUAL,
415 
417  AUTO,
418 
420  GUIDED,
421 
423  JOYSTICK,
424 
426  UNKNOWN
427  };
428 
430  enum class State {
432  DISARMED,
433 
435  ARMED,
436 
438  UNKNOWN
439  };
440 
442  Sys_status(
443  bool uplink_connected,
444  bool downlink_connected,
445  Control_mode control_mode,
446  State state,
447  std::chrono::seconds uptime);
448 
450  bool
451  operator==(const Sys_status&) const;
452 
455 
458 
461 
464 
466  std::chrono::seconds uptime;
467  };
468 
469  // Convenience function to check current flight mode.
470  bool
471  Is_flight_mode(ugcs::vsm::proto::Flight_mode);
472 
473  bool
474  Is_control_mode(ugcs::vsm::proto::Control_mode m);
475 
476  // Mission command mapping interface. Used to support current command reporting
477  // During mission flight.
478  //
479  // Here is how it works:
480  // 1. mission_upload command contains a list of sub_commands. VSM enumerates it as zero-based.
481  // This becomes the mission_command_id
482  // 2. Each mission command can produce any number of vehicle specific commands.
483  // 3. The mapping is sent back to server as a response to mission_upload command together with generated mission_id.
484  // 4. VSM reports current_vehicle_command to the server during mission flight.
485  // 5. Server uses this mapping maps vehicle_specific commands back to mission_commands.
486  // 6. mission_id is used to synchronize the command mapping with the server when
487  // the mapping is unknown to VSM (eg. after restart).
488  // 7. Server uses the command map only if the map exists and the reported mission_id in telemetry is equal to the
489  // mission_id received together with the map.
490  // 8. If server receives different mission_id it drops the current mapping.
492  {
493  public:
494  // Clear the command mapping and reset mission_id.
495  void
496  Reset();
497 
498  // Set the current_mission_command id as received from ucs.
499  // All vehicle specific commands produced by this mission command
500  // will map to this ID.
501  void
502  Set_current_command(int mission_command_id);
503 
504  // Map current_mission_command to this vehicle_command_id
505  // VSM must call this on each mission item it uploads to the vehicle.
506  // Or more precisely: on each command the vehicle is going to report as current command.
507  void
508  Add_command_mapping(int vehicle_specific_id);
509 
510  // Use this function to build mission_id.
511  // Used in two scenarios:
512  // 1) To report newly uploaded mission_id to server.
513  // 2) To calculate mission_id from downloaded mission from the vehicle.
514  // And report as telemetry when VSM has not seen the mission_upload.
515  // CRC32 algorithm is used to create a 32bit hash.
516  // IMPORTANT:
517  // Mission ID is calculated as hash from uploaded vehicle commands
518  // in such way that it can be recreated if vehicle supports mission
519  // download.
520  void
521  Accumulate_route_id(uint32_t hash);
522 
523  // Get the generated mission_id.
524  uint32_t
525  Get_route_id();
526 
527  // Fill in the mission_upload response payload with accumulated map and mission_id.
528  void
529  Fill_command_mapping_response(Proto_msg_ptr response);
530 
531  private:
532  // Mission mapper state.
533  int current_mission_command = -1;
534  // Current native command mapping to mission subcommands (zero based).
535  std::unordered_map<int, int> mission_command_map;
536  ugcs::vsm::Crc32 mission_id;
537  };
538 
543  void
544  Set_system_status(const Sys_status& sys_status);
545 
547  Sys_status
548  Get_system_status() const;
549 
551  Capabilities
552  Get_capabilities() const;
553 
555  void
556  Set_capabilities(const Capabilities& capabilities);
557 
559  Capability_states
560  Get_capability_states() const;
561 
563  void
564  Set_capability_states(const Capability_states& capability_states);
565 
566  unsigned int
567  Add_subdevice(Subdevice_type);
568 
570  Add_telemetry(
571  unsigned int subdevice,
572  const std::string& name,
573  ugcs::vsm::proto::Field_semantic semantic = ugcs::vsm::proto::FIELD_SEMANTIC_DEFAULT,
574  uint32_t timeout = 0);
575 
577  Add_telemetry(
578  unsigned int subdevice,
579  const std::string& name,
580  ugcs::vsm::Property::Value_type type,
581  uint32_t timeout = 0);
582 
583  // Remove telemetry field from default set created in Vehicle ctor.
584  // Used for vehicles which do not support default fields.
585  void
586  Remove_telemetry(Property::Ptr&);
587 
589  Add_command(
590  unsigned int subdevice,
591  const std::string& name,
592  bool as_command,
593  bool in_mission);
594 
595  /* End of user callable methods. */
596 
597 private:
598 
600  void
601  Calculate_system_id();
602 
604  Add_telemetry(
605  unsigned int subdevice,
606  Property::Ptr t);
607 
611  template<class Request_ptr>
612  void
613  Submit_vehicle_request(Request_ptr vehicle_request)
614  {
615  using Request = typename Request_ptr::element_type;
616  using Handle = typename Request::Handle;
617  typedef void (Vehicle::*Handler)(Handle);
618 
619  Handler method = &Vehicle::Handle_vehicle_request;
620  auto proc_handler = Make_callback(method,
621  Shared_from_this(),
622  Handle(vehicle_request));
623  vehicle_request->request->Set_processing_handler(proc_handler);
624  processor->Submit_request(vehicle_request->request);
625  }
626 
627  bool
628  Is_model_name_hardcoded();
630  const mavlink::MAV_AUTOPILOT autopilot;
631 
633  mavlink::MAV_STATE system_state = mavlink::MAV_STATE::MAV_STATE_UNINIT;
634 
636  Sys_status sys_status = Sys_status(
637  false, false, Sys_status::Control_mode::UNKNOWN,
638  Sys_status::State::UNKNOWN, std::chrono::seconds(0));
639 
641  Capabilities capabilities;
642 
644  Capability_states capability_states;
645 
648 
649  bool model_name_is_hardcoded;
650 
652  static std::mutex state_mutex;
653 
655  Optional<float> current_altitude_origin;
656 
657  /* Friend classes mostly for accessing system_id variable which we want
658  * to hide from SDK user.
659  */
660  friend class Ucs_vehicle_ctx;
661  friend class Ucs_transaction;
662  friend class Ucs_mission_clear_all_transaction;
663  friend class Ucs_task_upload_transaction;
664  friend class Ucs_vehicle_command_transaction;
665  friend class Cucs_processor;
666 };
667 
670 #define VEHICLE_LOG(level_, vehicle_, fmt_, ...) \
671  _LOG_WRITE_MSG(level_, "[%s:%s] " fmt_, \
672  (vehicle_).Get_model_name().c_str(), \
673  (vehicle_).Get_serial_number().c_str(), ## __VA_ARGS__)
674 
677 // @{
678 #define VEHICLE_LOG_DBG(vehicle_, fmt_, ...) \
679  VEHICLE_LOG(::ugcs::vsm::Log::Level::DEBUGGING, vehicle_, fmt_, ## __VA_ARGS__)
680 
681 #define VEHICLE_LOG_INF(vehicle_, fmt_, ...) \
682  VEHICLE_LOG(::ugcs::vsm::Log::Level::INFO, vehicle_, fmt_, ## __VA_ARGS__)
683 
684 #define VEHICLE_LOG_WRN(vehicle_, fmt_, ...) \
685  VEHICLE_LOG(::ugcs::vsm::Log::Level::WARNING, vehicle_, fmt_, ## __VA_ARGS__)
686 
687 #define VEHICLE_LOG_ERR(vehicle_, fmt_, ...) \
688  VEHICLE_LOG(::ugcs::vsm::Log::Level::ERROR, vehicle_, fmt_, ## __VA_ARGS__)
689 // @}
690 
691 } /* namespace vsm */
692 } /* namespace ugcs */
693 
694 #endif /* VEHICLE_H_ */
UGCS root namespace.
Definition: android-linux/ugcs/vsm/platform_sockets.h:27
Vehicle(mavlink::MAV_TYPE type, mavlink::MAV_AUTOPILOT autopilot, const Capabilities &capabilities, const std::string &serial_number, const std::string &model_name, int model_name_is_hardcoded=false, bool create_thread=true)
Constructor for a base class of user defined vehicle instance.
Generic request for implementing inter-threads communications and asynchronous operations.
Definition: request_container.h:37
Request worker.
State state
Current state of the vehicle.
Definition: vehicle.h:463
std::shared_ptr< Property > Ptr
Pointer type.
Definition: property.h:21
void Set_system_status(const Sys_status &sys_status)
Set system status of this vehicle.
Definition: crc32.h:14
virtual void On_disable()
Vehicle disable event handler.
Definition: vehicle.h:327
bool downlink_connected
State of the downlink connection from the vehicle.
Definition: vehicle.h:457
Definition: vehicle.h:491
Control_mode control_mode
Current control mode.
Definition: vehicle.h:460
Hasher for Vehicle shared pointer.
Definition: vehicle.h:164
Capabilities Get_capabilities() const
Get vehicle capabilities.
std::string port_name
Port name the vehicle is connected to.
Definition: vehicle.h:204
State
State of the vehicle.
Definition: vehicle.h:430
virtual void On_enable()
Vehicle enable event handler.
Definition: vehicle.h:320
const std::string & Get_model_name() const
Get model name of the vehicle.
Sys_status Get_system_status() const
Get current system status.
void Set_altitude_origin(float altitude_amsl)
Tell server that Vehicle knows its altitude_origin.
Enum_set< Capability > Capabilities
Container type for storing vehicle capabilities.
Definition: vehicle.h:92
const std::string & Get_port_name() const
Get port name the vehicle is connected to.
const std::string model_name
Model of the vehicle, e.g.
Definition: vehicle.h:201
const std::string & Get_autopilot_serial() const
Get autopilot serial number.
Capability
Capability of the vehicle.
Definition: vehicle.h:42
Result
Request completion result.
Definition: vehicle_request.h:26
Capability_states Get_capability_states() const
Get vehicle capability states.
std::shared_ptr< Vehicle > Ptr
Pointer type.
Definition: vehicle.h:36
Definition: vehicle.h:187
Callback< Callable, void, Args... >::Ptr Make_callback(Callable &&callable, Args &&...args)
Create a callback.
Definition: callback.h:389
std::chrono::seconds uptime
Vehicle uptime.
Definition: vehicle.h:466
std::string frame_type
Frame type.
Definition: vehicle.h:213
vehicle subsystems
Definition: vehicle.h:222
virtual ~Vehicle()
Make sure class is polymorphic.
Definition: vehicle.h:127
Handle of a specific vehicle request.
Definition: vehicle_request.h:160
Control_mode
Control mode of the vehicle.
Definition: vehicle.h:412
Handles interactions with CUCS.
Definition: cucs_processor.h:28
Capability_state
State of the vehicle capability.
Definition: vehicle.h:68
Definition: device.h:103
std::shared_ptr< Vsm_command > Ptr
Pointer type.
Definition: device.h:27
virtual void Handle_ucs_command(Ucs_request::Ptr ucs_request)
Message from ucs arrived.
const std::string & Get_serial_number() const
Get serial number of the vehicle.
void Process_requests()
Process requests assigned to vehicle in user thread, i.e.
Enum_set< Capability_state > Capability_states
Container type for storing vehicle capability states.
Definition: vehicle.h:95
void Set_capabilities(const Capabilities &capabilities)
Set vehicle capabilities.
const std::string serial_number
Serial number of the vehicle.
Definition: vehicle.h:198
const mavlink::MAV_TYPE type
Type of the vehicle.
Definition: vehicle.h:216
virtual void Handle_vehicle_request(Vehicle_task_request::Handle request)
Task has arrived from UCS and should be uploaded to the vehicle.
bool uplink_connected
State of the uplink connection to the vehicle.
Definition: vehicle.h:454
#define DEFINE_COMMON_CLASS(__class_name,...)
Use this macro to define some common attributes for a class.
Definition: utils.h:25
std::string autopilot_type
autopilot name
Definition: vehicle.h:210
void Reset_altitude_origin()
Tell server that current altitude origin must be dropped.
Convenience types for all specific vehicle requests.
std::string autopilot_serial
Serial number of the autopilot.
Definition: vehicle.h:207
std::shared_ptr< Ucs_request > Ptr
Pointer type.
Definition: device.h:88
System status of the vehicle.
Definition: vehicle.h:408
Base class for user-defined vehicles.
Definition: vehicle.h:35
void Set_capability_states(const Capability_states &capability_states)
Set vehicle capability states.