Class Message

Inheritance Relationships

Derived Types

Class Documentation

class Message

Message representation used by BabelFish. Wraps the memory of an actual type erased ROS2 message. Changes will affect the message that can be sent using the ROS runtime.

Subclassed by ros_babel_fish::ArrayMessageBase, ros_babel_fish::CompoundMessage, ros_babel_fish::ValueMessage< T >

Public Functions

explicit Message(MessageType type, std::shared_ptr<void> data)
virtual ~Message()
inline MessageType type() const
template<typename T>
inline T value() const

Convenience method to obtain the content of a ValueMessage as the given type. A type conversion is done if the type doesn’t match exactly. If the target type can not fit the source type, a warning is printed.

Template Parameters:

T – The type as which the value is retrieved

Throws:
Returns:

The value casted to the given type T

template<typename T>
inline T &as()

Convenience method that casts the message to the given type. Example:

Message &msg = getMessage();
CompoundMessage &compound = msg.as<CompoundMessage>();

Template Parameters:

T – Target type

Throws:

BabelFishException – If the message can not be casted to the target type

Returns:

Message casted to the target type as reference

template<typename T>
inline const T &as() const

Convenience method that casts the message to the given type. Example:

Message &msg = getMessage();
CompoundMessage &compound = msg.as<CompoundMessage>();

Template Parameters:

T – Target type

Throws:

BabelFishException – If the message can not be casted to the target type

Returns:

Message casted to the target type as reference

bool isTime() const
Returns:

True if this message is a builtin_interfaces/Time message and can be cast to rclcpp::Time using the value method.

bool isDuration() const
Returns:

True if this message is a builtin_interfaces/Duration message and can be cast to rclcpp::Duration using the value method.

virtual Message &operator[](const std::string &key)

Convenience method to access the child with the given key of a CompoundMessage.

Parameters:

key – The name or path of the child

Throws:

BabelFishException – If child access by key is not supported.

Returns:

The child message accessed by the given key

virtual const Message &operator[](const std::string &key) const

Convenience method to access the child with the given key of a CompoundMessage.

Parameters:

key – The name or path of the child

Throws:

BabelFishException – If child access by key is not supported.

Returns:

The child message accessed by the given key

template<typename T>
bool operator==(const T &other) const
bool operator==(const Message &other) const
bool operator==(const char *c) const
bool operator==(const wchar_t *c) const
template<typename T>
bool operator!=(const T &other) const
template<>
bool value() const
template<>
uint8_t value() const
template<>
uint16_t value() const
template<>
uint32_t value() const
template<>
uint64_t value() const
template<>
int8_t value() const
template<>
int16_t value() const
template<>
int32_t value() const
template<>
int64_t value() const
template<>
float value() const
template<>
double value() const
template<>
long double value() const
template<>
std::string value() const
template<>
char16_t value() const
template<>
std::wstring value() const
template<>
rclcpp::Time value() const
template<>
rclcpp::Duration value() const

Protected Functions

inline void move(std::shared_ptr<void> new_data)
inline virtual void onMoved()
template<typename T, typename U>
void checkValueEqual(const U &other, bool &result) const
Message(const Message &other) = default
virtual bool _isMessageEqual(const Message &other) const = 0
virtual void _assign(const Message &other) = 0
inline unsigned char *data_ptr()
inline const unsigned char *data_ptr() const

Protected Attributes

std::shared_ptr<void> data_
MessageType type_

Friends

friend class CompoundMessage
friend class CompoundArrayMessage_