Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[humble] Add --log-level to ros2 bag play and record #1655

Merged
merged 2 commits into from
May 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion ros2bag/ros2bag/verb/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,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 main(self, *, args): # noqa: D102
qos_profile_overrides = {} # Specify a valid default
Expand Down Expand Up @@ -145,7 +149,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 @@ -164,6 +164,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102
'--use-sim-time', action='store_true', default=False,
help='Use simulation time for message timestamps by subscribing to the /clock topic. '
'Until first /clock message is received, no messages will be written to bag.')
parser.add_argument(
'--log-level', type=str, default='info',
choices=['debug', 'info', 'warn', 'error', 'fatal'],
help='Logging level.')
self._subparser = parser

def main(self, *, args): # noqa: D102
Expand Down Expand Up @@ -247,7 +251,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)
Expand Down
45 changes: 40 additions & 5 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 @@ -108,9 +139,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 @@ -142,9 +174,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 @@ -322,11 +355,13 @@ PYBIND11_MODULE(_transport, m) {

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

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"))
.def_static("cancel", &rosbag2_py::Recorder::cancel)
Expand Down
21 changes: 21 additions & 0 deletions rosbag2_py/test/test_transport.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@


from common import get_rosbag_options, wait_for
import pytest
import rclpy
from rclpy.qos import QoSProfile
import rosbag2_py
Expand Down Expand Up @@ -48,6 +49,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)


def test_record_cancel(tmp_path):
bag_path = str(tmp_path / 'test_record_cancel')
storage_options, converter_options = get_rosbag_options(bag_path)
Expand Down
Loading