Class CompoundMessage

Inheritance Relationships

Base Type

Class Documentation

class CompoundMessage : public ros_babel_fish::Message

Public Functions

CompoundMessage()

Creates an invalid instance of a compound message.

CompoundMessage(MessageMembersIntrospection members, std::shared_ptr<void> data)
explicit CompoundMessage(MessageMembersIntrospection members, rosidl_runtime_cpp::MessageInitialization init = rosidl_runtime_cpp::MessageInitialization::ALL)
CompoundMessage(const CompoundMessage &other)

Creates a copy of the CompoundMessage pointing at the same message. Use clone() to get an independent copy of this message.

CompoundMessage(CompoundMessage&&) = default
~CompoundMessage() override = default
std::string datatype() const

Datatype of the message, e.g., geometry_msgs::msg::Pose.

std::string name() const

Name of the message, e.g., geometry_msgs/msg/Pose.

bool containsKey(const std::string &key) const
std::vector<std::string> keys() const
std::string keyAt(size_t index)
inline uint32_t memberCount() const
CompoundMessage &operator=(const Message &other)
CompoundMessage &operator=(const builtin_interfaces::msg::Time &value)
CompoundMessage &operator=(const builtin_interfaces::msg::Duration &value)
CompoundMessage &operator=(const rclcpp::Time &value)
CompoundMessage &operator=(const rclcpp::Duration &value)
CompoundMessage &operator=(const CompoundMessage &other)
CompoundMessage &operator=(CompoundMessage &&other) noexcept
virtual Message &operator[](const std::string &key) override

Accesses submessage with the given key.

Throws:
  • std::out_of_range – If key is not in message.

  • std::runtime_error – If message was not initialized for key.

Parameters:

key – The name of the member you want to access.

Returns:

The value of the member with the given name.

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

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

std::vector<Message::SharedPtr> values()
std::vector<Message::ConstSharedPtr> values() const
std::shared_ptr<const void> type_erased_message() const
std::shared_ptr<void> type_erased_message()
CompoundMessage clone() const

Creates a copy of this compound message.

bool isValid() const

Protected Functions

virtual void onMoved() override
void initValues() const
Message::SharedPtr operator[](size_t index)
Message::ConstSharedPtr operator[](size_t index) const
virtual bool _isMessageEqual(const Message &other) const override
virtual void _assign(const Message &other) override

Protected Attributes

MessageMembersIntrospection members_
mutable std::vector<Message::SharedPtr> values_
mutable bool initialized_values_ = false