Skip to content

Commit

Permalink
Add --log-level to ros2 bag play and record (#1654)
Browse files Browse the repository at this point in the history
Signed-off-by: Roman Sokolkov <[email protected]>
Co-authored-by: Michael Orlov <[email protected]>
  • Loading branch information
r7vme and MichaelOrlov authored May 14, 2024
1 parent a360d9b commit 1ad354a
Show file tree
Hide file tree
Showing 4 changed files with 71 additions and 8 deletions.
6 changes: 5 additions & 1 deletion ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -145,6 +145,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'By default, if loaned message can be used, messages are published as loaned '
'message. It can help to reduce the number of data copies, so there is a greater '
'benefit for sending big data.')
parser.add_argument(
'--log-level', type=str, default='info',
choices=['debug', 'info', 'warn', 'error', 'fatal'],
help='Logging level.')

def get_playback_until_from_arg_group(self, playback_until_sec, playback_until_nsec) -> int:
nano_scale = 1000 * 1000 * 1000
Expand Down Expand Up @@ -202,7 +206,7 @@ def main(self, *, args): # noqa: D102
play_options.wait_acked_timeout = args.wait_for_all_acked
play_options.disable_loan_message = args.disable_loan_message

player = Player()
player = Player(args.log_level)
try:
player.play(storage_options, play_options)
except KeyboardInterrupt:
Expand Down
6 changes: 5 additions & 1 deletion ros2bag/ros2bag/verb/record.py
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'--snapshot-mode', action='store_true',
help='Enable snapshot mode. Messages will not be written to the bagfile until '
'the "/rosbag2_recorder/snapshot" service is called.')
parser.add_argument(
'--log-level', type=str, default='info',
choices=['debug', 'info', 'warn', 'error', 'fatal'],
help='Logging level.')

# Storage configuration
add_writer_storage_plugin_extensions(parser)
Expand Down Expand Up @@ -255,7 +259,7 @@ def main(self, *, args): # noqa: D102
record_options.ignore_leaf_topics = args.ignore_leaf_topics
record_options.use_sim_time = args.use_sim_time

recorder = Recorder()
recorder = Recorder(args.log_level)

try:
recorder.record(storage_options, record_options, args.node_name)
Expand Down
47 changes: 41 additions & 6 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <algorithm>
#include <csignal>
#include <chrono>
#include <memory>
Expand All @@ -37,6 +38,36 @@ typedef std::unordered_map<std::string, rclcpp::QoS> QoSMap;
namespace
{

class Arguments
{
public:
explicit Arguments(const std::vector<std::string> & args)
: arguments_(args)
{
std::for_each(
arguments_.begin(), arguments_.end(),
[this](const std::string & arg) {
pointers_.push_back(const_cast<char *>(arg.c_str()));
}
);
pointers_.push_back(nullptr);
}

char ** argv()
{
return arguments_.empty() ? nullptr : pointers_.data();
}

[[nodiscard]] int argc() const
{
return static_cast<int>(arguments_.size());
}

private:
std::vector<std::string> arguments_;
std::vector<char *> pointers_;
};

rclcpp::QoS qos_from_handle(const py::handle source)
{
PyObject * raw_obj = PyObject_CallMethod(source.ptr(), "get_c_qos_profile", "");
Expand Down Expand Up @@ -130,9 +161,10 @@ namespace rosbag2_py
class Player
{
public:
Player()
explicit Player(const std::string & log_level = "info")
{
rclcpp::init(0, nullptr);
Arguments arguments({"--ros-args", "--log-level", log_level});
rclcpp::init(arguments.argc(), arguments.argv());
}

virtual ~Player()
Expand Down Expand Up @@ -190,9 +222,10 @@ class Player
class Recorder
{
public:
Recorder()
explicit Recorder(const std::string & log_level = "info")
{
rclcpp::init(0, nullptr);
Arguments arguments({"--ros-args", "--log-level", log_level});
rclcpp::init(arguments.argc(), arguments.argv());
}

virtual ~Recorder()
Expand Down Expand Up @@ -394,13 +427,15 @@ PYBIND11_MODULE(_transport, m) {
;

py::class_<rosbag2_py::Player>(m, "Player")
.def(py::init())
.def(py::init<>())
.def(py::init<const std::string &>())
.def("play", &rosbag2_py::Player::play, py::arg("storage_options"), py::arg("play_options"))
.def("burst", &rosbag2_py::Player::burst)
;

py::class_<rosbag2_py::Recorder>(m, "Recorder")
.def(py::init())
.def(py::init<>())
.def(py::init<const std::string &>())
.def(
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"),
py::arg("node_name") = "rosbag2_recorder")
Expand Down
20 changes: 20 additions & 0 deletions rosbag2_py/test/test_transport.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,26 @@ def test_options_qos_conversion():
assert record_options.topic_qos_profile_overrides == simple_overrides


def test_player_log_level():
rosbag2_py.Player() # Test for default constructor
valid_log_level = 'debug'
rosbag2_py.Player(valid_log_level)

invalid_log_level = 'xxx'
with pytest.raises(RuntimeError):
rosbag2_py.Player(invalid_log_level)


def test_recoder_log_level():
rosbag2_py.Recorder() # Test for default constructor
valid_log_level = 'debug'
rosbag2_py.Recorder(valid_log_level)

invalid_log_level = 'xxx'
with pytest.raises(RuntimeError):
rosbag2_py.Recorder(invalid_log_level)


@pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS)
def test_record_cancel(tmp_path, storage_id):
bag_path = str(tmp_path / 'test_record_cancel')
Expand Down

0 comments on commit 1ad354a

Please sign in to comment.