diff --git a/rosbag2_py/src/rosbag2_py/_rosbag2_py.cpp b/rosbag2_py/src/rosbag2_py/_rosbag2_py.cpp index ad6cda8007..78109a8dfd 100644 --- a/rosbag2_py/src/rosbag2_py/_rosbag2_py.cpp +++ b/rosbag2_py/src/rosbag2_py/_rosbag2_py.cpp @@ -30,74 +30,6 @@ namespace py = pybind11; namespace rosbag2_py { -class StorageOptions -{ -public: - StorageOptions() {} - - std::string get_uri() - { - return storage_options_.uri; - } - - void set_uri(const std::string & uri) - { - storage_options_.uri = uri; - } - - std::string get_storage_id() - { - return storage_options_.storage_id; - } - - void set_storage_id(const std::string & id) - { - storage_options_.storage_id = id; - } - - uint64_t get_max_bagfile_size() - { - return storage_options_.max_bagfile_size; - } - - void set_max_bagfile_size(uint64_t size) - { - storage_options_.max_bagfile_size = size; - } - -private: - rosbag2::StorageOptions storage_options_; -}; - -class ConverterOptions -{ -public: - ConverterOptions() {} - - std::string get_input_serialization_format() - { - return converter_options_.input_serialization_format; - } - - void set_input_serialization_format(const std::string & format) - { - converter_options_.input_serialization_format = format; - } - - std::string get_output_serialization_format() - { - return converter_options_.output_serialization_format; - } - - void set_output_serialization_format(const std::string & format) - { - converter_options_.output_serialization_format = format; - } - -private: - rosbag2::ConverterOptions converter_options_; -}; - class SequentialReader { public: @@ -106,19 +38,9 @@ class SequentialReader {} void open( - rosbag2_py::StorageOptions & s_opts_py, - rosbag2_py::ConverterOptions & c_opts_py) + rosbag2::StorageOptions & storage_options, + rosbag2::ConverterOptions & converter_options) { - rosbag2::StorageOptions storage_options{}; - storage_options.uri = s_opts_py.get_uri(); - storage_options.storage_id = s_opts_py.get_storage_id(); - - rosbag2::ConverterOptions converter_options{}; - converter_options.input_serialization_format = - c_opts_py.get_input_serialization_format(); - converter_options.output_serialization_format = - c_opts_py.get_output_serialization_format(); - reader_.open(storage_options, converter_options); } @@ -166,23 +88,17 @@ PYBIND11_MODULE(_rosbag2_py, m) { .def("has_next", &rosbag2_py::SequentialReader::has_next) .def("get_all_topics_and_types", &rosbag2_py::SequentialReader::get_all_topics_and_types); - pybind11::class_(m, "StorageOptions") + pybind11::class_(m, "StorageOptions") .def(pybind11::init()) - .def("get_uri", &rosbag2_py::StorageOptions::get_uri) - .def("set_uri", &rosbag2_py::StorageOptions::set_uri) - .def("get_storage_id", &rosbag2_py::StorageOptions::get_storage_id) - .def("set_storage_id", &rosbag2_py::StorageOptions::set_storage_id) - .def("get_max_bagfile_size", &rosbag2_py::StorageOptions::get_max_bagfile_size) - .def("set_max_bagfile_size", &rosbag2_py::StorageOptions::set_max_bagfile_size); - - pybind11::class_(m, "ConverterOptions") + .def_readwrite("uri", &rosbag2::StorageOptions::uri) + .def_readwrite("storage_id", &rosbag2::StorageOptions::storage_id) + .def_readwrite("max_bagfile_size", + &rosbag2::StorageOptions::max_bagfile_size); + + pybind11::class_(m, "ConverterOptions") .def(pybind11::init()) - .def("get_input_serialization_format", - &rosbag2_py::ConverterOptions::get_input_serialization_format) - .def("set_input_serialization_format", - &rosbag2_py::ConverterOptions::set_input_serialization_format) - .def("get_output_serialization_format", - &rosbag2_py::ConverterOptions::get_input_serialization_format) - .def("set_output_serialization_format", - &rosbag2_py::ConverterOptions::set_output_serialization_format); + .def_readwrite("input_serialization_format", + &rosbag2::ConverterOptions::input_serialization_format) + .def_readwrite("output_serialization_format", + &rosbag2::ConverterOptions::output_serialization_format); }