Skip to content

Commit

Permalink
ROS1 rosbag2rawlog: Add support for GPS
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Dec 5, 2024
1 parent 8dc76dd commit 9ecdc49
Show file tree
Hide file tree
Showing 2 changed files with 36 additions and 0 deletions.
34 changes: 34 additions & 0 deletions apps/rosbag2rawlog/rosbag2rawlog_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <mrpt/obs/CObservationPointCloud.h>
#include <mrpt/obs/CObservationRotatingScan.h>
#include <mrpt/poses/CPose3DQuat.h>
#include <mrpt/ros1bridge/gps.h>
#include <mrpt/ros1bridge/imu.h>
#include <mrpt/ros1bridge/laser_scan.h>
#include <mrpt/ros1bridge/point_cloud2.h>
Expand Down Expand Up @@ -398,6 +399,33 @@ Obs toIMU(
return {mrptObs};
}

Obs toGPS(
std::string_view msg,
const rosbag::MessageInstance& rosmsg,
const std::optional<mrpt::poses::CPose3D>& fixedSensorPose)
{
auto gps = rosmsg.instantiate<sensor_msgs::NavSatFix>();

auto mrptObs = mrpt::obs::CObservationGPS::Create();

mrptObs->sensorLabel = msg;
mrptObs->timestamp = mrpt::ros1bridge::fromROS(gps->header.stamp);

// Convert data:
mrpt::ros1bridge::fromROS(*gps, *mrptObs);

bool sensorPoseOK = findOutSensorPose(
mrptObs->sensorPose, gps->header.frame_id, arg_base_link_frame.getValue(), fixedSensorPose);
if (!sensorPoseOK)
{
std::cerr << "Warning: dropping one observation of type '" << msg
<< "' due to missing /tf data.\n";
return {};
}

return {mrptObs};
}

Obs toOdometry(std::string_view msg, const rosbag::MessageInstance& rosmsg)
{
auto odo = rosmsg.instantiate<nav_msgs::Odometry>();
Expand Down Expand Up @@ -676,6 +704,12 @@ class Transcriber
{ return toIMU(sensorName, m, fixedSensorPose); };
m_lookup[sensor.at("topic").as<std::string>()].emplace_back(callback);
}
else if (sensorType == "CObservationGPS")
{
auto callback = [=](const rosbag::MessageInstance& m)
{ return toGPS(sensorName, m, fixedSensorPose); };
m_lookup[sensor.at("topic").as<std::string>()].emplace_back(callback);
}
else if (sensorType == "CObservationOdometry")
{
auto callback = [=](const rosbag::MessageInstance& m) { return toOdometry(sensorName, m); };
Expand Down
2 changes: 2 additions & 0 deletions doc/source/doxygen-docs/changelog.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
\page changelog Change Log

# Version 2.14.7: UNRELEASED
- Changes in apps:
- rosbag2rawlog (ROS1): Implement conversion of NavSatFix -> mrpt::obs::CObservationGPS
- Build system:
- `mrpt-*-config.cmake` files now enforce the search of cmake dependencies in CONFIG mode, to avoid being foolish by deprecated `FindXXX()` lying around.

Expand Down

0 comments on commit 9ecdc49

Please sign in to comment.