template class ugcs::vsm::mavlink::Value_array<Char, size>¶
Overview¶
Partial specialization for characters array so it can be conveniently used with string semantic. More…
#include <mavlink.h> template <size_t size> class Value_array<Char, size> { public: // methods Char& operator [] (size_t index); size_t Get_length() const; std::string Get_string() const; void Reset(); bool operator == (const char* str); bool operator != (const char* str); Value_array& operator = (const char* str); Value_array& operator = (const std::string& str); };
Detailed Documentation¶
Partial specialization for characters array so it can be conveniently used with string semantic.
Methods¶
Char& operator [] (size_t index)
Access operator.
size_t Get_length() const
Get string length.
In MAVLink character string may be NULL terminated or may not be if it fully occupies the array.
Returns:
String length in bytes.
std::string Get_string() const
Get string value for the characters array.
void Reset()
Reset all array values to UgCS default values (zeros for string).
bool operator == (const char* str)
Compare with string.
bool operator != (const char* str)
Compare with string.
Value_array& operator = (const char* str)
Assign string to the characters array.
In case the string exceeds the array size it is truncated without terminated NULL character (as per MAVLink strings description).
Parameters:
str |
String to assign. |
Value_array& operator = (const std::string& str)
Assign string to the characters array.
In case the string exceeds the array size it is truncated without terminated NULL character (as per MAVLink strings description).
Parameters:
str |
String to assign. |