Skip to content

Commit

Permalink
introduce defaults for the C++ API (#452)
Browse files Browse the repository at this point in the history
* minimal c++ API test

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* introduce defaults

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* open overload for simple uri string

Signed-off-by: Karsten Knese <karsten@openrobotics.org>

* set sqlite3 as a constant

Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 authored and Emerson Knapp committed Feb 2, 2021
1 parent 678bb98 commit c2f2889
Show file tree
Hide file tree
Showing 7 changed files with 78 additions and 17 deletions.
25 changes: 23 additions & 2 deletions rosbag2_cpp/include/rosbag2_cpp/reader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <vector>

#include "rosbag2_cpp/converter_options.hpp"
#include "rosbag2_cpp/readers/sequential_reader.hpp"
#include "rosbag2_cpp/storage_options.hpp"
#include "rosbag2_cpp/visibility_control.hpp"

Expand Down Expand Up @@ -50,10 +51,28 @@ class BaseReaderInterface;
class ROSBAG2_CPP_PUBLIC Reader final
{
public:
explicit Reader(std::unique_ptr<reader_interfaces::BaseReaderInterface> reader_impl);
explicit Reader(
std::unique_ptr<reader_interfaces::BaseReaderInterface> reader_impl =
std::make_unique<readers::SequentialReader>());

~Reader();

/**
* Opens an existing bagfile and prepare it for reading messages.
* The bagfile must exist.
* This must be called before any other function is used.
*
* \note This will open URI with the default storage options
* * using sqlite3 storage backend
* * using no converter options, storing messages with the incoming serialization format
* \sa rmw_get_serialization_format.
* For specifications, please see \sa open, which let's you specify
* more storage and converter options.
*
* \param storage_uri URI of the storage to open.
**/
void open(const std::string & uri);

/**
* Throws if file could not be opened.
* This must be called before any other function is used.
Expand All @@ -67,7 +86,9 @@ class ROSBAG2_CPP_PUBLIC Reader final
* \param storage_options Options to configure the storage
* \param converter_options Options for specifying the output data format
*/
void open(const StorageOptions & storage_options, const ConverterOptions & converter_options);
void open(
const StorageOptions & storage_options,
const ConverterOptions & converter_options = ConverterOptions());

/**
* Ask whether the underlying bagfile contains at least one more message.
Expand Down
24 changes: 22 additions & 2 deletions rosbag2_cpp/include/rosbag2_cpp/writer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "rosbag2_cpp/converter_options.hpp"
#include "rosbag2_cpp/storage_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/topic_metadata.hpp"
Expand All @@ -50,18 +51,37 @@ class BaseWriterInterface;
class ROSBAG2_CPP_PUBLIC Writer final
{
public:
explicit Writer(std::unique_ptr<rosbag2_cpp::writer_interfaces::BaseWriterInterface> writer_impl);
explicit Writer(
std::unique_ptr<rosbag2_cpp::writer_interfaces::BaseWriterInterface> writer_impl =
std::make_unique<writers::SequentialWriter>());

~Writer();

/**
* Opens a new bagfile and prepare it for writing messages. The bagfile must not exist.
* This must be called before any other function is used.
*
* \note This will open URI with the default storage options
* * using sqlite3 storage backend
* * using no converter options, storing messages with the incoming serialization format
* \sa rmw_get_serialization_format.
* For specifications, please see \sa open, which let's you specify
* more storage and converter options.
*
* \param storage_uri URI of the storage to open.
**/
void open(const std::string & uri);

/**
* Opens a new bagfile and prepare it for writing messages. The bagfile must not exist.
* This must be called before any other function is used.
*
* \param storage_options Options to configure the storage
* \param converter_options options to define in which format incoming messages are stored
**/
void open(const StorageOptions & storage_options, const ConverterOptions & converter_options);
void open(
const StorageOptions & storage_options,
const ConverterOptions & converter_options = ConverterOptions());

/**
* Create a new topic in the underlying storage. Needs to be called for every topic used within
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
<depend>rosidl_typesupport_introspection_cpp</depend>
<depend>shared_queues_vendor</depend>

<exec_depend>rosbag2_storage_default_plugins</exec_depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
13 changes: 13 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include "rosbag2_cpp/reader.hpp"

#include <memory>
#include <string>
#include <utility>
#include <vector>

Expand All @@ -34,6 +35,18 @@ Reader::~Reader()
reader_impl_->reset();
}

void Reader::open(const std::string & uri)
{
rosbag2_cpp::StorageOptions storage_options;
storage_options.uri = uri;
storage_options.storage_id = "sqlite3";
storage_options.max_bagfile_size = 0; // default
storage_options.max_cache_size = 0; // default

rosbag2_cpp::ConverterOptions converter_options{};
return open(storage_options, converter_options);
}

void Reader::open(
const StorageOptions & storage_options,
const ConverterOptions & converter_options)
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,6 +227,8 @@ void SequentialReader::check_converter_serialization_format(
const std::string & converter_serialization_format,
const std::string & storage_serialization_format)
{
if (converter_serialization_format.empty()) {return;}

if (converter_serialization_format != storage_serialization_format) {
converter_ = std::make_unique<Converter>(
storage_serialization_format,
Expand Down
12 changes: 12 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
namespace rosbag2_cpp
{

static constexpr char const * kDefaultStorageID = "sqlite3";

Writer::Writer(std::unique_ptr<rosbag2_cpp::writer_interfaces::BaseWriterInterface> writer_impl)
: writer_impl_(std::move(writer_impl))
{}
Expand All @@ -40,6 +42,16 @@ Writer::~Writer()
writer_impl_.reset();
}

void Writer::open(const std::string & uri)
{
rosbag2_cpp::StorageOptions storage_options;
storage_options.uri = uri;
storage_options.storage_id = kDefaultStorageID;

rosbag2_cpp::ConverterOptions converter_options{};
return open(storage_options, converter_options);
}

void Writer::open(
const StorageOptions & storage_options, const ConverterOptions & converter_options)
{
Expand Down
17 changes: 4 additions & 13 deletions rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,18 +44,9 @@ TEST(TestRosbag2CPPAPI, minimal_writer_example)
// in case the bag was previously not cleaned up
rcpputils::fs::remove_all(rosbag_directory);

rosbag2_cpp::StorageOptions storage_options;
storage_options.uri = rosbag_directory.string();
storage_options.storage_id = "sqlite3";
storage_options.max_bagfile_size = 0; // default
storage_options.max_cache_size = 0; // default
rosbag2_cpp::ConverterOptions converter_options;
converter_options.input_serialization_format = "cdr";
converter_options.output_serialization_format = "cdr";

{
rosbag2_cpp::Writer writer(std::make_unique<rosbag2_cpp::writers::SequentialWriter>());
writer.open(storage_options, converter_options);
rosbag2_cpp::Writer writer;
writer.open(rosbag_directory.string());

auto bag_message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
auto ret = rcutils_system_time_now(&bag_message->time_stamp);
Expand All @@ -78,8 +69,8 @@ TEST(TestRosbag2CPPAPI, minimal_writer_example)
}

{
rosbag2_cpp::Reader reader(std::make_unique<rosbag2_cpp::readers::SequentialReader>());
reader.open(storage_options, converter_options);
rosbag2_cpp::Reader reader;
reader.open(rosbag_directory.string());
while (reader.has_next()) {
auto bag_message = reader.read_next();

Expand Down

0 comments on commit c2f2889

Please sign in to comment.