Program Listing for File writer.hpp

Return to documentation for file (/tmp/ws/src/rosbag2/rosbag2_cpp/include/rosbag2_cpp/writer.hpp)

// Copyright 2018, Bosch Software Innovations GmbH.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef ROSBAG2_CPP__WRITER_HPP_
#define ROSBAG2_CPP__WRITER_HPP_

#include <memory>
#include <mutex>
#include <string>
#include <unordered_map>
#include <vector>

#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
#include "rclcpp/time.hpp"

#include "rosbag2_cpp/bag_events.hpp"
#include "rosbag2_cpp/converter_options.hpp"
#include "rosbag2_cpp/visibility_control.hpp"
#include "rosbag2_cpp/writers/sequential_writer.hpp"

#include "rosbag2_storage/serialized_bag_message.hpp"
#include "rosbag2_storage/storage_options.hpp"
#include "rosbag2_storage/topic_metadata.hpp"

// This is necessary because of using stl types here. It is completely safe, because
// a) the member is not accessible from the outside
// b) there are no inline functions.
#ifdef _WIN32
# pragma warning(push)
# pragma warning(disable:4251)
#endif

namespace rosbag2_cpp
{
namespace writer_interfaces
{
class BaseWriterInterface;
}  // namespace writer_interfaces

class ROSBAG2_CPP_PUBLIC Writer final
{
public:
  explicit Writer(
    std::unique_ptr<rosbag2_cpp::writer_interfaces::BaseWriterInterface> writer_impl =
    std::make_unique<writers::SequentialWriter>());

  ~Writer();

  void open(const std::string & uri);

  void open(
    const rosbag2_storage::StorageOptions & storage_options,
    const ConverterOptions & converter_options = ConverterOptions());

  void create_topic(const rosbag2_storage::TopicMetadata & topic_with_type);

  bool take_snapshot();

  void remove_topic(const rosbag2_storage::TopicMetadata & topic_with_type);

  void write(std::shared_ptr<rosbag2_storage::SerializedBagMessage> message);

  void write(
    std::shared_ptr<rosbag2_storage::SerializedBagMessage> message,
    const std::string & topic_name,
    const std::string & type_name,
    const std::string & serialization_format = "cdr");

  [[deprecated(
    "Use write(std::shared_ptr<rclcpp::SerializedMessage> message," \
    " const std::string & topic_name," \
    " const std::string & type_name," \
    " const rclcpp::Time & time) instead."
  )]]
  void write(
    const rclcpp::SerializedMessage & message,
    const std::string & topic_name,
    const std::string & type_name,
    const rclcpp::Time & time);

  void write(
    std::shared_ptr<rclcpp::SerializedMessage> message,
    const std::string & topic_name,
    const std::string & type_name,
    const rclcpp::Time & time);

  template<class MessageT>
  void write(
    const MessageT & message,
    const std::string & topic_name,
    const rclcpp::Time & time)
  {
    auto serialized_msg = std::make_shared<rclcpp::SerializedMessage>();

    rclcpp::Serialization<MessageT> serialization;
    serialization.serialize_message(&message, serialized_msg.get());
    return write(serialized_msg, topic_name, rosidl_generator_traits::name<MessageT>(), time);
  }

  writer_interfaces::BaseWriterInterface & get_implementation_handle() const
  {
    return *writer_impl_;
  }

  /*
   * \brief Add callbacks for events that may occur during bag writing.
   * \param callbacks the structure containing the callback to add for each event.
   */
  void add_event_callbacks(bag_events::WriterEventCallbacks & callbacks);

  void close();

private:
  std::mutex writer_mutex_;
  std::unique_ptr<rosbag2_cpp::writer_interfaces::BaseWriterInterface> writer_impl_;
};

}  // namespace rosbag2_cpp

#ifdef _WIN32
# pragma warning(pop)
#endif

#endif  // ROSBAG2_CPP__WRITER_HPP_