diff --git a/ros2bag/ros2bag/verb/record.py b/ros2bag/ros2bag/verb/record.py index e9e5f5a1f9..3979e2f6e1 100644 --- a/ros2bag/ros2bag/verb/record.py +++ b/ros2bag/ros2bag/verb/record.py @@ -174,6 +174,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102 '--use-sim-time', action='store_true', default=False, help='Use simulation time.' ) + parser.add_argument( + '--node-name', type=str, default='rosbag2_recorder', + help='Specify the recorder node name. Default is rosbag2_recorder.' + ) self._subparser = parser def main(self, *, args): # noqa: D102 @@ -259,7 +263,7 @@ def main(self, *, args): # noqa: D102 recorder = Recorder() try: - recorder.record(storage_options, record_options) + recorder.record(storage_options, record_options, args.node_name) except KeyboardInterrupt: pass diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index dc8f3eeae3..1b51f30429 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -210,7 +210,8 @@ class Recorder void record( const rosbag2_storage::StorageOptions & storage_options, - RecordOptions & record_options) + RecordOptions & record_options, + std::string & node_name) { if (record_options.rmw_serialization_format.empty()) { record_options.rmw_serialization_format = std::string(rmw_get_serialization_format()); @@ -218,7 +219,7 @@ class Recorder auto writer = rosbag2_transport::ReaderWriterFactory::make_writer(record_options); auto recorder = std::make_shared( - std::move(writer), storage_options, record_options); + std::move(writer), storage_options, record_options, node_name); recorder->record(); exec_->add_node(recorder); @@ -356,7 +357,9 @@ PYBIND11_MODULE(_transport, m) { py::class_(m, "Recorder") .def(py::init()) - .def("record", &rosbag2_py::Recorder::record) + .def( + "record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"), + py::arg("node_name") = "rosbag2_recorder") .def("cancel", &rosbag2_py::Recorder::cancel) ;