【cartographer without ros】七、Rosbag的引入和使用

上一节介绍了LandmarkData数据相关转换,到此阐述了在不带ros环境中,对cartographer所需要的几类传感器数据进行处理。

本节就将介绍在脱离ros环境后,我们仍可以引入和使用Rosbag,以对外部数据进行存包读包,方便我们对cartographer的建图和定位做离线模拟和调试。

目录

1:安装rosbag并引用

2:初始化rosbag,并打开对应读写文件

3:将传感器数据写入rosbag

4:在rosbag中读取传感器数据


1:安装rosbag并引用

安装:

sudo apt-get install librosbag-dev

如果按照此系列第一篇博客【cartographer without ros】一、不带Ros的快速安装配置环境,此时应该已经安装了rosbag。
引用:

#include <rosbag/bag.h>
#include <rosbag/view.h>

2:初始化rosbag,并打开对应读写文件

rosbag::Bag bag_;
if(read)
{
    bag_.open(bagName,rosbag::bagmode::Read);
}
else
{
    bag_.open(bagName,rosbag::bagmode::Write);
}

3:将传感器数据写入rosbag

template void Write<cartographer::sensor::TimedPointCloudData>(
    cartographer::sensor::TimedPointCloudData measurement);
template void Write<cartographer::sensor::OdometryData>(
    cartographer::sensor::OdometryData measurement);
template void Write<cartographer::sensor::ImuData>(
    cartographer::sensor::ImuData measurement);
template void Write<cartographer::sensor::LandmarkData>(
    cartographer::sensor::LandmarkData measurement);
template <typename T>
void Write(T measurement)
{
  std::string sensorname = typeid(measurement).name();
  ros::Time time = RosFromCarto(CartoFromSys());
  auto msg = ToRosMsg(measurement);
  bag_.write(sensorname, time, msg);
}

4:在rosbag中读取传感器数据

void Read()
{
    rosbag::View view(bag_);
    for (rosbag::MessageInstance m : view)
    {
        if (m.getTopic() == typeid(cartographer::sensor::TimedPointCloudData).name())
        {
            sensor_msgs::LaserScanConstPtr rosMsg = m.instantiate<sensor_msgs::LaserScan>();
            if (rosMsg != NULL)
            {
                cartographer::sensor::TimedPointCloudData pointcloud_data = ToCartoSensor(*rosMsg);
            }
        }
        else if (m.getTopic() == typeid(cartographer::sensor::OdometryData).name())
        {
            nav_msgs::OdometryConstPtr rosMsg = m.instantiate<nav_msgs::Odometry>();
            if (rosMsg != NULL)
            {
                cartographer::sensor::OdometryData odometry_data = ToCartoSensor(*rosMsg);
            }
        }
        else if ( m.getTopic() == typeid(cartographer::sensor::ImuData).name())
        {
            sensor_msgs::ImuConstPtr rosMsg = m.instantiate<sensor_msgs::Imu>();
            if (rosMsg != NULL)
            {
               cartographer::sensor::ImuData imu_data = ToCartoSensor(*rosMsg);
            }
        } 
        else if (m.getTopic() == typeid(cartographer::sensor::LandmarkData).name())
        {
            cartographer_ros_msgs::LandmarkListConstPtr rosMsg = m.instantiate<cartographer_ros_msgs::LandmarkList>();
            if (rosMsg != NULL)
            {
               cartographer::sensor::LandmarkData landmark_data = ToCartoSensor(*rosMsg);
            }
        }
    }
}

【完】


下一节会介绍在自己的工程中,引入调用cartographer,来实现建图,存储,定位等功能。

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

CloudFlame

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值