VSM C++ SDK
Vehicle Specific Modules SDK
ugcs::vsm::Vehicle Class Reference

Base class for user-defined vehicles. More...

#include <vehicle.h>

Inheritance diagram for ugcs::vsm::Vehicle:
ugcs::vsm::Device

Classes

class  Command_map
 
class  Hasher
 Hasher for Vehicle shared pointer. More...
 
class  Subdevice
 
struct  Subsystems
 vehicle subsystems More...
 
class  Sys_status
 System status of the vehicle. More...
 

Public Types

typedef std::shared_ptr< VehiclePtr
 Pointer type.
 
typedef std::weak_ptr< VehicleWeak_ptr
 Pointer type.
 
typedef Enum_set< CapabilityCapabilities
 Container type for storing vehicle capabilities. More...
 
typedef Enum_set< Capability_stateCapability_states
 Container type for storing vehicle capability states. More...
 
enum  Capability {
  ARM_AVAILABLE, DISARM_AVAILABLE, AUTO_MODE_AVAILABLE, MANUAL_MODE_AVAILABLE,
  RETURN_HOME_AVAILABLE, TAKEOFF_AVAILABLE, LAND_AVAILABLE, EMERGENCY_LAND_AVAILABLE,
  CAMERA_TRIGGER_AVAILABLE, WAYPOINT_AVAILABLE, PAUSE_MISSION_AVAILABLE, RESUME_MISSION_AVAILABLE,
  GUIDED_MODE_AVAILABLE, JOYSTICK_MODE_AVAILABLE, PAYLOAD_POWER_AVAILABLE, SWITCH_VIDEO_SOURCE_AVAILABLE,
  DIRECT_VEHICLE_CONTROL_AVAILABLE, DIRECT_PAYLOAD_CONTROL_AVAILABLE, LAST
}
 Capability of the vehicle. More...
 
enum  Capability_state {
  ARM_ENABLED, DISARM_ENABLED, AUTO_MODE_ENABLED, MANUAL_MODE_ENABLED,
  RETURN_HOME_ENABLED, TAKEOFF_ENABLED, LAND_ENABLED, EMERGENCY_LAND_ENABLED,
  CAMERA_TRIGGER_ENABLED, WAYPOINT_ENABLED, PAUSE_MISSION_ENABLED, RESUME_MISSION_ENABLED,
  GUIDED_MODE_ENABLED, JOYSTICK_MODE_ENABLED, PAYLOAD_POWER_ENABLED, SWITCH_VIDEO_SOURCE_ENABLED,
  DIRECT_VEHICLE_CONTROL_ENABLED, DIRECT_PAYLOAD_CONTROL_ENABLED, LAST
}
 State of the vehicle capability. More...
 
- Public Types inherited from ugcs::vsm::Device
typedef std::shared_ptr< DevicePtr
 Pointer type.
 
typedef std::weak_ptr< DeviceWeak_ptr
 Pointer type.
 
typedef Callback_proxy< void, std::vector< Property::Ptr > > Command_handler
 
typedef Callback_proxy< void, uint32_t, Proto_msg_ptr > Response_sender
 Completion handler type of the request. More...
 

Public Member Functions

 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. More...
 
virtual ~Vehicle ()
 Make sure class is polymorphic. More...
 
 Vehicle (const Vehicle &)=delete
 Disable copying. More...
 
void Process_requests ()
 Process requests assigned to vehicle in user thread, i.e. More...
 
const std::string & Get_serial_number () const
 Get serial number of the vehicle. More...
 
const std::string & Get_model_name () const
 Get model name of the vehicle.
 
const std::string & Get_port_name () const
 Get port name the vehicle is connected to. More...
 
const std::string & Get_autopilot_serial () const
 Get autopilot serial number.
 
ugcs::vsm::mavlink::MAV_AUTOPILOT Get_autopilot () const
 
const std::string & Get_autopilot_type () const
 
- Public Member Functions inherited from ugcs::vsm::Device
 Device (bool create_thread=true)
 
void Enable ()
 Enable the instance. More...
 
void Disable ()
 Disable the instance. More...
 
bool Is_enabled ()
 Vehicle enable/disable status. More...
 
 Device (const Device &)=delete
 Disable copying. More...
 
void Process_requests ()
 Process requests assigned to vehicle in user thread, i.e. More...
 
void On_ucs_message (ugcs::vsm::proto::Vsm_message message, Response_sender completion_handler=Response_sender(), ugcs::vsm::Request_completion_context::Ptr completion_ctx=nullptr)
 
template<typename Type >
void Add_property (const std::string &name, Type value, Property::Value_type value_type)
 
template<typename Type >
void Add_property (const std::string &name, ugcs::vsm::proto::Field_semantic semantic, Type value)
 
uint32_t Get_session_id ()
 
Request_completion_context::Ptr Get_completion_ctx ()
 Get default completion context of the device. More...
 

Static Public Member Functions

template<typename... Args>
static Ptr Create (Args &&...args)
 Create an instance. More...
 
- Static Public Member Functions inherited from ugcs::vsm::Device
template<typename... Args>
static Ptr Create (Args &&...args)
 Create an instance. More...
 

Protected Types

enum  Subdevice_type { SUBDEVICE_TYPE_FC = 1, SUBDEVICE_TYPE_CAMERA = 2, SUBDEVICE_TYPE_GIMBAL = 3, SUBDEVICE_TYPE_ADSB_TRANSPONDER = 4 }
 

Protected Member Functions

virtual void On_enable ()
 Vehicle enable event handler. More...
 
virtual void On_disable ()
 Vehicle disable event handler. More...
 
void Set_rc_loss_actions (std::initializer_list< proto::Failsafe_action > actions)
 
void Set_gps_loss_actions (std::initializer_list< proto::Failsafe_action > actions)
 
void Set_low_battery_actions (std::initializer_list< proto::Failsafe_action > actions)
 
void Reset_altitude_origin ()
 Tell server that current altitude origin must be dropped. More...
 
void Set_altitude_origin (float altitude_amsl)
 Tell server that Vehicle knows its altitude_origin. More...
 
virtual void Handle_ucs_command (Ucs_request::Ptr ucs_request)
 Message from ucs arrived.
 
void Command_completed (ugcs::vsm::Vehicle_request::Result result, const std::string &status_text, Ucs_request::Ptr ucs_request)
 
void Command_failed (Ucs_request::Ptr ucs_request, const std::string &status_text, proto::Status_code code=ugcs::vsm::proto::STATUS_FAILED)
 
void Command_succeeded (Ucs_request::Ptr ucs_request)
 
virtual void Handle_vehicle_request (Vehicle_task_request::Handle request)
 Task has arrived from UCS and should be uploaded to the vehicle.
 
virtual void Handle_vehicle_request (Vehicle_command_request::Handle request)
 UCS sending a command to the vehicle.
 
virtual void Fill_register_msg (ugcs::vsm::proto::Vsm_message &)
 
bool Is_flight_mode (ugcs::vsm::proto::Flight_mode)
 
bool Is_control_mode (ugcs::vsm::proto::Control_mode m)
 
void Set_system_status (const Sys_status &sys_status)
 Set system status of this vehicle. More...
 
Sys_status Get_system_status () const
 Get current system status. More...
 
Capabilities Get_capabilities () const
 Get vehicle capabilities. More...
 
void Set_capabilities (const Capabilities &capabilities)
 Set vehicle capabilities. More...
 
Capability_states Get_capability_states () const
 Get vehicle capability states. More...
 
void Set_capability_states (const Capability_states &capability_states)
 Set vehicle capability states. More...
 
unsigned int Add_subdevice (Subdevice_type)
 
Property::Ptr Add_telemetry (unsigned int subdevice, const std::string &name, ugcs::vsm::proto::Field_semantic semantic=ugcs::vsm::proto::FIELD_SEMANTIC_DEFAULT, uint32_t timeout=0)
 
Property::Ptr Add_telemetry (unsigned int subdevice, const std::string &name, ugcs::vsm::Property::Value_type type, uint32_t timeout=0)
 
void Remove_telemetry (Property::Ptr &)
 
Vsm_command::Ptr Add_command (unsigned int subdevice, const std::string &name, bool as_command, bool in_mission)
 
- Protected Member Functions inherited from ugcs::vsm::Device
void Register ()
 Register device instance to UCS processor. More...
 
void Unregister ()
 Unregister device instance from UCS processor. More...
 
Request_processor::Ptr Get_processing_ctx ()
 Get default processing context of the vehicle. More...
 
void Send_ucs_message (Proto_msg_ptr msg)
 
Vsm_command::Ptr Get_command (int id)
 
Property::Ptr Add_telemetry (const std::string &name, ugcs::vsm::proto::Field_semantic sem=ugcs::vsm::proto::FIELD_SEMANTIC_DEFAULT, uint32_t timeout=0)
 
Property::Ptr Add_telemetry (const std::string &name, Property::Value_type type, uint32_t timeout=0)
 
void Remove_telemetry (Property::Ptr &t_field)
 
Vsm_command::Ptr Add_command (const std::string &name, bool as_command, bool in_mission)
 
void Add_status_message (const std::string &m)
 
void Commit_to_ucs ()
 

Protected Attributes

const std::string serial_number
 Serial number of the vehicle. More...
 
const std::string model_name
 Model of the vehicle, e.g. More...
 
std::string port_name
 Port name the vehicle is connected to. More...
 
std::string autopilot_serial
 Serial number of the autopilot. More...
 
std::string autopilot_type
 autopilot name
 
std::string frame_type
 Frame type.
 
const mavlink::MAV_TYPE type
 Type of the vehicle. More...
 
ugcs::vsm::proto::Vehicle_type vehicle_type
 
std::vector< Subdevicesubdevices
 
Subsystems subsystems
 
ugcs::vsm::Optional< ugcs::vsm::proto::Flight_mode > current_flight_mode
 
ugcs::vsm::Property::Ptr t_control_mode = nullptr
 
ugcs::vsm::Property::Ptr t_is_armed = nullptr
 
ugcs::vsm::Property::Ptr t_uplink_present = nullptr
 
ugcs::vsm::Property::Ptr t_downlink_present = nullptr
 
ugcs::vsm::Property::Ptr t_main_voltage = nullptr
 
ugcs::vsm::Property::Ptr t_main_current = nullptr
 
ugcs::vsm::Property::Ptr t_gcs_link_quality = nullptr
 
ugcs::vsm::Property::Ptr t_rc_link_quality = nullptr
 
ugcs::vsm::Property::Ptr t_latitude = nullptr
 
ugcs::vsm::Property::Ptr t_longitude = nullptr
 
ugcs::vsm::Property::Ptr t_altitude_raw = nullptr
 
ugcs::vsm::Property::Ptr t_altitude_amsl = nullptr
 
ugcs::vsm::Property::Ptr t_ground_speed = nullptr
 
ugcs::vsm::Property::Ptr t_air_speed = nullptr
 
ugcs::vsm::Property::Ptr t_course = nullptr
 
ugcs::vsm::Property::Ptr t_vertical_speed = nullptr
 
ugcs::vsm::Property::Ptr t_pitch = nullptr
 
ugcs::vsm::Property::Ptr t_roll = nullptr
 
ugcs::vsm::Property::Ptr t_heading = nullptr
 
ugcs::vsm::Property::Ptr t_gps_fix = nullptr
 
ugcs::vsm::Property::Ptr t_satellite_count = nullptr
 
ugcs::vsm::Property::Ptr t_altitude_origin = nullptr
 
ugcs::vsm::Property::Ptr t_home_altitude_amsl = nullptr
 
ugcs::vsm::Property::Ptr t_home_altitude_raw = nullptr
 
ugcs::vsm::Property::Ptr t_home_latitude = nullptr
 
ugcs::vsm::Property::Ptr t_home_longitude = nullptr
 
ugcs::vsm::Property::Ptr t_target_altitude_amsl = nullptr
 
ugcs::vsm::Property::Ptr t_target_altitude_raw = nullptr
 
ugcs::vsm::Property::Ptr t_target_latitude = nullptr
 
ugcs::vsm::Property::Ptr t_target_longitude = nullptr
 
ugcs::vsm::Property::Ptr t_current_command = nullptr
 
ugcs::vsm::Property::Ptr t_current_mission_id = nullptr
 
ugcs::vsm::Property::Ptr t_flight_mode = nullptr
 
ugcs::vsm::Property::Ptr t_native_flight_mode = nullptr
 
ugcs::vsm::Property::Ptr t_fence_enabled = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_mission_upload = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_auto = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_arm = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_disarm = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_waypoint = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_guided = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_manual = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_pause = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_resume = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_rth = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_land_command = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_joystick = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_direct_vehicle_control = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_takeoff_command = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_emergency_land = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_trigger_command = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_adsb_set_ident = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_adsb_set_mode = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_direct_payload_control = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_power = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_video_source = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_adsb_set_parameter = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_servo = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_repeat_servo = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_fence = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_trigger_calibration = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_wait = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_move = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_speed = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_home = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_poi = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_heading = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_panorama = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_trigger_mission = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_by_time = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_camera_by_distance = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_land_mission = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_takeoff_mission = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_set_parameter = nullptr
 
ugcs::vsm::Vsm_command::Ptr c_payload_control = nullptr
 
Property::Ptr p_rc_loss_action = nullptr
 
Property::Ptr p_gps_loss_action = nullptr
 
Property::Ptr p_low_battery_action = nullptr
 
Property::Ptr p_wp_turn_type = nullptr
 
- Protected Attributes inherited from ugcs::vsm::Device
Request_completion_context::Ptr completion_ctx
 
Request_processor::Ptr processor
 
std::chrono::time_point< std::chrono::system_clock > begin_of_epoch
 
std::unordered_map< std::string, Property::Ptrproperties
 

Friends

class Ucs_vehicle_ctx
 
class Ucs_transaction
 
class Ucs_mission_clear_all_transaction
 
class Ucs_task_upload_transaction
 
class Ucs_vehicle_command_transaction
 
class Cucs_processor
 

Detailed Description

Base class for user-defined vehicles.

It contains interface to SDK services which can be used as base class methods calls, and abstract interface which must be implemented by the device. Instance creation should be done by Vehicle::Create() method.

Member Typedef Documentation

Container type for storing vehicle capabilities.

Container type for storing vehicle capability states.

Member Enumeration Documentation

Capability of the vehicle.

This is legacy enum. do not add new commands here.

State of the vehicle capability.

This is legacy enum. do not add new commands here.

Constructor & Destructor Documentation

ugcs::vsm::Vehicle::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.

Vehicle instance is identified by serial number and model name which combination should be unique in the whole UgCS domain (i.e. all interconnected UCS and VSM systems).

Parameters
typeType of the vehicle.
autopilotAutopilot type of the vehicle.
capabilitiesCapabilities of the vehicle.
serial_numberSerial number of the vehicle.
model_nameModel name of the vehicle.
model_name_is_hardcodedtell the UCS that vehicle name is not specified by user or taken from the autopilot but hardcoded in VSM code instead.
create_threadIf true, then separate thread is automatically created for vehicle instance which allows to using blocking methods in the context of this vehicle without blocking other vehicles, otherwise vehicle instance thread is not created and user is supposed to call Vehicle::Process_requests method to process requests pending for this vehicle. It is recommended to leave this value as default, i.e. "true".
virtual ugcs::vsm::Vehicle::~Vehicle ( )
inlinevirtual

Make sure class is polymorphic.

ugcs::vsm::Vehicle::Vehicle ( const Vehicle )
delete

Disable copying.

Member Function Documentation

template<typename... Args>
static Ptr ugcs::vsm::Vehicle::Create ( Args &&...  args)
inlinestatic

Create an instance.

Capabilities ugcs::vsm::Vehicle::Get_capabilities ( ) const
protected

Get vehicle capabilities.

Capability_states ugcs::vsm::Vehicle::Get_capability_states ( ) const
protected

Get vehicle capability states.

const std::string& ugcs::vsm::Vehicle::Get_port_name ( ) const

Get port name the vehicle is connected to.

const std::string& ugcs::vsm::Vehicle::Get_serial_number ( ) const

Get serial number of the vehicle.

Sys_status ugcs::vsm::Vehicle::Get_system_status ( ) const
protected

Get current system status.

virtual void ugcs::vsm::Vehicle::On_disable ( )
inlineprotectedvirtual

Vehicle disable event handler.

Can be overridden by derived class, if necessary.

Reimplemented from ugcs::vsm::Device.

virtual void ugcs::vsm::Vehicle::On_enable ( )
inlineprotectedvirtual

Vehicle enable event handler.

Can be overridden by derived class, if necessary.

Reimplemented from ugcs::vsm::Device.

void ugcs::vsm::Vehicle::Process_requests ( )

Process requests assigned to vehicle in user thread, i.e.

the thread which calls this method. Supposed to be called only when vehicle is created without its own thread.

void ugcs::vsm::Vehicle::Reset_altitude_origin ( )
protected

Tell server that current altitude origin must be dropped.

(calibration needed to match reported altitude to real world)

Use this when VSM knows that currently reported Rel_altitude changed unexpectedly. For example if vehicle resets the reported altitude on ARM.

void ugcs::vsm::Vehicle::Set_altitude_origin ( float  altitude_amsl)
protected

Tell server that Vehicle knows its altitude_origin.

Use this when VSM knows that reported Rel_altitude origin has changed. Ardupilot does that on home location change.

void ugcs::vsm::Vehicle::Set_capabilities ( const Capabilities capabilities)
protected

Set vehicle capabilities.

void ugcs::vsm::Vehicle::Set_capability_states ( const Capability_states capability_states)
protected

Set vehicle capability states.

void ugcs::vsm::Vehicle::Set_system_status ( const Sys_status sys_status)
protected

Set system status of this vehicle.

Should be called when system status changes, but at least with reasonable granularity to update system uptime.

Member Data Documentation

std::string ugcs::vsm::Vehicle::autopilot_serial
protected

Serial number of the autopilot.

(empty if not available)

const std::string ugcs::vsm::Vehicle::model_name
protected

Model of the vehicle, e.g.

Arducopter, Mikrokopter etc.

std::string ugcs::vsm::Vehicle::port_name
protected

Port name the vehicle is connected to.

("COM12" or "127.0.0.1:5440")

const std::string ugcs::vsm::Vehicle::serial_number
protected

Serial number of the vehicle.

const mavlink::MAV_TYPE ugcs::vsm::Vehicle::type
protected

Type of the vehicle.


The documentation for this class was generated from the following file: