Program Listing for File compound_message.hpp

Return to documentation for file (include/ros_babel_fish/messages/compound_message.hpp)

// Copyright (c) 2021 Stefan Fabian. All rights reserved.
// Licensed under the MIT license. See LICENSE file in the project root for full license information.

#ifndef ROS_BABEL_FISH_COMPOUND_MESSAGE_HPP
#define ROS_BABEL_FISH_COMPOUND_MESSAGE_HPP

#include "message.hpp"
#include "ros_babel_fish/idl/type_support.hpp"
#include <rosidl_runtime_cpp/message_initialization.hpp>

#include <vector>

namespace ros_babel_fish
{

class CompoundMessage final : public Message
{
public:
  RCLCPP_SMART_PTR_DEFINITIONS( CompoundMessage )


  CompoundMessage();

  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 );

  CompoundMessage( CompoundMessage && ) = default;

  ~CompoundMessage() override = default;

  std::string datatype() const;

  std::string name() const;

  bool containsKey( const std::string &key ) const;

  std::vector<std::string> keys() const;

  std::string keyAt( size_t index );

  uint32_t memberCount() const { return members_->member_count_; }

  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;

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

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

  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;

  bool isValid() const;

protected:
  void onMoved() override;

  void initValues() const;

  Message::SharedPtr operator[]( size_t index );

  Message::ConstSharedPtr operator[]( size_t index ) const;

  bool _isMessageEqual( const Message &other ) const override;

  void _assign( const Message &other ) override;

  MessageMembersIntrospection members_;
  mutable std::vector<Message::SharedPtr> values_;
  mutable bool initialized_values_ = false;
};
} // namespace ros_babel_fish

#endif // ROS_BABEL_FISH_COMPOUND_MESSAGE_HPP