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

Add simple bag player examples #1580

Closed
wants to merge 19 commits into from
Closed
Show file tree
Hide file tree
Changes from 12 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
15 changes: 14 additions & 1 deletion rosbag2_examples/rosbag2_examples_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,13 @@ find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rosbag2_cpp REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(std_msgs REQUIRED)

add_executable(simple_bag_recorder src/simple_bag_recorder.cpp)
target_link_libraries(simple_bag_recorder
rclcpp::rclcpp
rosbag2_cpp::rosbag2_cpp
${example_interfaces_TARGETS}
${std_msgs_TARGETS}
)

install(TARGETS
Expand Down Expand Up @@ -58,6 +59,18 @@ install(TARGETS
DESTINATION lib/${PROJECT_NAME}
)

add_executable(simple_bag_player src/simple_bag_player.cpp)
target_link_libraries(simple_bag_player
rclcpp::rclcpp
rosbag2_cpp::rosbag2_cpp
${std_msgs_TARGETS}
)

install(TARGETS
simple_bag_player
DESTINATION lib/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
1 change: 1 addition & 0 deletions rosbag2_examples/rosbag2_examples_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<depend>rclcpp</depend>
<depend>rosbag2_cpp</depend>
<depend>example_interfaces</depend>
<depend>std_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
84 changes: 84 additions & 0 deletions rosbag2_examples/rosbag2_examples_cpp/src/simple_bag_player.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
// Copyright 2024 Open Source Robotics Foundation
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <iostream>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/serialization.hpp"
#include "rosbag2_cpp/reader.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

class SimpleBagPlayer : public rclcpp::Node
{
public:
explicit SimpleBagPlayer(const std::string & bag_filename)
: Node("playback_node")
sangteak601 marked this conversation as resolved.
Show resolved Hide resolved
{
publisher_ = this->create_publisher<std_msgs::msg::String>("chatter", 10);

timer_ = this->create_wall_timer(
100ms,
[this]() {return this->timer_callback();}
sangteak601 marked this conversation as resolved.
Show resolved Hide resolved
sangteak601 marked this conversation as resolved.
Show resolved Hide resolved
);

reader_.open(bag_filename);
}

private:
void timer_callback()
{
while (reader_.has_next()) {
rosbag2_storage::SerializedBagMessageSharedPtr msg = reader_.read_next();

if (msg->topic_name != "chatter") {
continue;
}

rclcpp::SerializedMessage serialized_msg(*msg->serialized_data);
std_msgs::msg::String::SharedPtr ros_msg = std::make_shared<std_msgs::msg::String>();

serialization_.deserialize_message(&serialized_msg, ros_msg.get());
sangteak601 marked this conversation as resolved.
Show resolved Hide resolved

publisher_->publish(*ros_msg);
std::cout << ros_msg->data << "\n";

break;
}
}

rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;

rclcpp::Serialization<std_msgs::msg::String> serialization_;
rosbag2_cpp::Reader reader_;
};

int main(int argc, char ** argv)
{
if (argc != 2) {
std::cerr << "Usage: " << argv[0] << " <bag>" << std::endl;
return 1;
}

rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<SimpleBagPlayer>(argv[1]));
rclcpp::shutdown();

return 0;
}
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include <memory>

#include "example_interfaces/msg/string.hpp"
#include "std_msgs/msg/string.hpp"
#include "rclcpp/rclcpp.hpp"

#include "rosbag2_cpp/writer.hpp"
Expand All @@ -31,18 +31,18 @@ class SimpleBagRecorder : public rclcpp::Node

writer_->open("my_bag");

subscription_ = create_subscription<example_interfaces::msg::String>(
subscription_ = create_subscription<std_msgs::msg::String>(
"chatter", 10, std::bind(&SimpleBagRecorder::topic_callback, this, _1));
}

private:
void topic_callback(std::shared_ptr<rclcpp::SerializedMessage> msg) const
{
rclcpp::Time time_stamp = this->now();
writer_->write(msg, "chatter", "example_interfaces/msg/String", time_stamp);
writer_->write(msg, "chatter", "std_msgs/msg/String", time_stamp);
}

rclcpp::Subscription<example_interfaces::msg::String>::SharedPtr subscription_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
std::unique_ptr<rosbag2_cpp::Writer> writer_;
};

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
# Copyright 2023 Open Source Robotics Foundation, Inc.
sangteak601 marked this conversation as resolved.
Show resolved Hide resolved
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import sys

import rclpy
from rclpy.node import Node
from rclpy.serialization import deserialize_message
import rosbag2_py
from std_msgs.msg import String


class SimpleBagPlayer(Node):

def __init__(self, bag_filename):
super().__init__('simple_bag_player')
self.reader = rosbag2_py.SequentialReader()
storage_options = rosbag2_py._storage.StorageOptions(
uri=bag_filename,
storage_id='sqlite3')
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if i am not mistaken, this is intentionally enabled as sqlite3? but this bag file can be also red from simple_bag_player.cpp, because it reads the meta data from the bag file and use the appropriate storage plugin if available? just checking this because user does not meet the failure during the tutorial.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It was set as sqlite3 in simple_bag_recorder.py. I don't know the reason exactly.
It is possible to read sqlite3 files from simple_bag_player.cpp, but the opposite(reading mcap files from simple_bag_player.py) isn't.

Maybe we can delete storage_id?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No, i think that is okay with current code. this also includes an example how to specify the storage id, i think that is fine.

converter_options = rosbag2_py._storage.ConverterOptions('', '')
self.reader.open(storage_options, converter_options)

self.publisher = self.create_publisher(String, 'chatter', 10)
self.timer = self.create_timer(0.1, self.timer_callback)

def timer_callback(self):
while self.reader.has_next():
msg = self.reader.read_next()
if msg[0] != 'chatter':
continue
ros_msg = deserialize_message(msg[1], String)
self.publisher.publish(ros_msg)
self.get_logger().info(ros_msg.data)


def main(args=None):
rclpy.init(args=args)
sbr = SimpleBagPlayer(sys.argv[1])
rclpy.spin(sbr)
rclpy.shutdown()


if __name__ == '__main__':
main()
1 change: 1 addition & 0 deletions rosbag2_examples/rosbag2_examples_py/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
entry_points={
'console_scripts': [
'simple_bag_recorder = rosbag2_examples_py.simple_bag_recorder:main',
'simple_bag_player = rosbag2_examples_py.simple_bag_player:main',
'data_generator_node = rosbag2_examples_py.data_generator_node:main',
'data_generator_executable = rosbag2_examples_py.data_generator_executable:main',
],
Expand Down