VSM C++ SDK
Vehicle Specific Modules SDK
ugcs::vsm::mavlink::Value< T, id, initial_value > Class Template Reference

Field value in MAVLink message. More...

#include <mavlink.h>

Public Member Functions

 Value (T value=initial_value)
 Construct value. More...
 
Valueoperator= (T value)
 Assign new value. More...
 
 operator T () const
 Cast to underlying type. More...
 
Get () const
 Get the value of underlying type. More...
 
constexpr Field_type_id Get_type_id ()
 Get type ID for this value. More...
 
void Reset ()
 Reset to default value used in UgCS as a "not present" indication. More...
 
bool Is_reset () const
 Check, if the field is reset. More...
 

Detailed Description

template<typename T, Field_type_id id, long initial_value = 0>
class ugcs::vsm::mavlink::Value< T, id, initial_value >

Field value in MAVLink message.

Parameters
TInteger underlying type.
idID for the type.
initial_valueInitial value for the field. It's type is fixed to integer because floating point numbers cannot be template parameters.

Constructor & Destructor Documentation

template<typename T, Field_type_id id, long initial_value = 0>
ugcs::vsm::mavlink::Value< T, id, initial_value >::Value ( value = initial_value)
inline

Construct value.

Parameters
valueValue in host byte order.

Member Function Documentation

template<typename T, Field_type_id id, long initial_value = 0>
T ugcs::vsm::mavlink::Value< T, id, initial_value >::Get ( ) const
inline

Get the value of underlying type.

Returns
Value in host byte order.
template<typename T, Field_type_id id, long initial_value = 0>
constexpr Field_type_id ugcs::vsm::mavlink::Value< T, id, initial_value >::Get_type_id ( )
inline

Get type ID for this value.

template<typename T, Field_type_id id, long initial_value = 0>
bool ugcs::vsm::mavlink::Value< T, id, initial_value >::Is_reset ( ) const
inline

Check, if the field is reset.

template<typename T, Field_type_id id, long initial_value = 0>
ugcs::vsm::mavlink::Value< T, id, initial_value >::operator T ( ) const
inline

Cast to underlying type.

Returns
Value in host byte order.
template<typename T, Field_type_id id, long initial_value = 0>
Value& ugcs::vsm::mavlink::Value< T, id, initial_value >::operator= ( value)
inline

Assign new value.

Parameters
valueValue in host byte order.
template<typename T, Field_type_id id, long initial_value = 0>
void ugcs::vsm::mavlink::Value< T, id, initial_value >::Reset ( )
inline

Reset to default value used in UgCS as a "not present" indication.


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