Skip to content

Commit

Permalink
Hide ros2 dependencies from public .h
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Dec 24, 2023
1 parent 9e023b2 commit a359552
Show file tree
Hide file tree
Showing 3 changed files with 44 additions and 21 deletions.
2 changes: 2 additions & 0 deletions mola_input_rosbag2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ find_package(sensor_msgs REQUIRED)
find_package(rosbag2_cpp REQUIRED)
find_package(tf2_msgs REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)

find_mola_package(mola_kernel)

Expand All @@ -43,6 +44,7 @@ mola_add_library(
tf2::tf2
rosbag2_cpp::rosbag2_cpp
#nav_msgs
tf2_geometry_msgs::tf2_geometry_msgs
tf2_msgs::tf2_msgs__rosidl_typesupport_cpp
sensor_msgs::sensor_msgs_library
cv_bridge::cv_bridge
Expand Down
27 changes: 17 additions & 10 deletions mola_input_rosbag2/include/mola_input_rosbag2/Rosbag2Dataset.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,22 @@
#include <mrpt/io/CFileGZInputStream.h>
#include <mrpt/obs/CSensoryFrame.h>
#include <mrpt/serialization/CArchive.h>
#include <tf2/buffer_core.h>

#include <list>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/serialization.hpp>
#include <rosbag2_cpp/converter_options.hpp>
#include <rosbag2_cpp/readers/sequential_reader.hpp>

// forward decls to isolate build dependencies downstream:
namespace tf2
{
class BufferCore;
}
namespace rosbag2_cpp::readers
{
class SequentialReader;
}
namespace rosbag2_storage
{
class SerializedBagMessage;
}

namespace mola
{
Expand Down Expand Up @@ -72,9 +81,8 @@ class Rosbag2Dataset : public RawDataSourceBase, public OfflineDatasetSource
double time_warp_scale_ = 1.0;
size_t read_ahead_length_ = 15;

rosbag2_cpp::readers::SequentialReader reader_;
std::vector<rosbag2_storage::TopicMetadata> topics_;
rosbag2_storage::BagMetadata bagMetaData_;
std::shared_ptr<rosbag2_cpp::readers::SequentialReader> reader_;
size_t bagMessageCount_ = 0;

using SF = mrpt::obs::CSensoryFrame;

Expand Down Expand Up @@ -110,8 +118,7 @@ class Rosbag2Dataset : public RawDataSourceBase, public OfflineDatasetSource
std::map<std::string, std::vector<CallbackFunction>> lookup_;
std::set<std::string> unhandledTopics_;

std::shared_ptr<tf2::BufferCore> tfBuffer_ =
std::make_shared<tf2::BufferCore>();
std::shared_ptr<tf2::BufferCore> tfBuffer_;

template <bool isStatic>
Obs toTf(const rosbag2_storage::SerializedBagMessage& rosmsg);
Expand Down
36 changes: 25 additions & 11 deletions mola_input_rosbag2/src/Rosbag2Dataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,23 @@
#include <mrpt/ros2bridge/pose.h>
#include <mrpt/ros2bridge/time.h>
#include <mrpt/system/filesystem.h>
#include <tf2/buffer_core.h>
#include <tf2/convert.h>
#include <tf2/exceptions.h>

#include <cv_bridge/cv_bridge.hpp>
#include <nav_msgs/msg/odometry.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/serialization.hpp>
#include <rosbag2_cpp/converter_options.hpp>
#include <rosbag2_cpp/readers/sequential_reader.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/imu.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/int32.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_msgs/msg/tf_message.hpp>

using namespace mola;
Expand All @@ -57,7 +63,11 @@ MRPT_INITIALIZER(do_register_Rosbag2Dataset)
MOLA_REGISTER_MODULE(Rosbag2Dataset);
}

Rosbag2Dataset::Rosbag2Dataset() { this->setLoggerName("Rosbag2Dataset"); }
Rosbag2Dataset::Rosbag2Dataset()
{
this->setLoggerName("Rosbag2Dataset");
tfBuffer_ = std::make_shared<tf2::BufferCore>();
}

void Rosbag2Dataset::initialize(const Yaml& c)
{
Expand Down Expand Up @@ -99,29 +109,31 @@ void Rosbag2Dataset::initialize(const Yaml& c)

MRPT_LOG_INFO_STREAM("Opening: " << storage_options.uri);

reader_.open(storage_options, converter_options);
reader_ = std::make_shared<rosbag2_cpp::readers::SequentialReader>();
reader_->open(storage_options, converter_options);

topics_ = reader_.get_all_topics_and_types();
std::vector<rosbag2_storage::TopicMetadata> topics =
reader_->get_all_topics_and_types();

bagMetaData_ = reader_.get_metadata();
auto bagMetaData = reader_->get_metadata();
bagMessageCount_ = bagMetaData.message_count;

MRPT_LOG_INFO_STREAM(
"List of topics found in the bag (" << bagMetaData_.message_count
<< " msgs"
"List of topics found in the bag (" << bagMessageCount_ << " msgs"
<< ")");

// Build map: topic name -> type:
std::map<std::string, std::string> topic2type;

for (const auto& t : topics_)
for (const auto& t : topics)
{
topic2type[t.name] = t.type;

MRPT_LOG_INFO_STREAM(" " << t.name << " (" << t.type << ")");
}

read_ahead_.clear();
read_ahead_.resize(bagMetaData_.message_count);
read_ahead_.resize(bagMessageCount_);
rosbag_next_idx_ = 0;

// Begin of code adapted from "Transcriber" class from rosbag2rawlog:
Expand All @@ -146,7 +158,7 @@ void Rosbag2Dataset::initialize(const Yaml& c)
// create list automatically:
sensorsYaml = mrpt::containers::yaml::Sequence();

for (const auto& t : topics_)
for (const auto& t : topics)
{
auto itType = mapTopic2Class.find(t.type);
if (itType == mapTopic2Class.end())
Expand Down Expand Up @@ -387,6 +399,8 @@ void Rosbag2Dataset::doReadAhead(const std::optional<size_t>& requestedIndex)
{
MRPT_START

ASSERT_(initialized_);

// ensure we have observation data at the desired read point, plus a few
// more:
const auto startIdx = rosbag_next_idx_;
Expand All @@ -408,7 +422,7 @@ void Rosbag2Dataset::doReadAhead(const std::optional<size_t>& requestedIndex)
ASSERT_EQUAL_(rosbag_next_idx_write_, idx);
rosbag_next_idx_write_++;

auto serialized_message = reader_.read_next();
auto serialized_message = reader_->read_next();
SF::Ptr sf = to_mrpt(*serialized_message);
ASSERT_(sf);

Expand All @@ -428,7 +442,7 @@ size_t Rosbag2Dataset::datasetSize() const
{
ASSERTMSG_(initialized_, "You must call initialize() first");

return bagMetaData_.message_count;
return bagMessageCount_;
}

mrpt::obs::CSensoryFrame::Ptr Rosbag2Dataset::datasetGetObservations(
Expand Down

0 comments on commit a359552

Please sign in to comment.