本文是一篇关于CyberRT使用体验的笔记。首先,简要介绍了CyberRT的基本概念、特点及其在自动驾驶领域的应用。接着,详细描述了作者在使用CyberRT过程中的实际操作步骤,包括环境搭建、模块配置、消息通信等关键环节。此外,文章还分享了一些使用技巧、遇到的问题及解决方案,并对CyberRT的性能和稳定性进行了评价。最后,总结了使用CyberRT的体会和感悟,展望了其在自动驾驶领域的未来发展前景。
1. 头文件
#include <cyber/cyber.h>
#include <cyber/record/record_reader.h>
#include <cyber/record/record_viewer.h>
2. 预定义
using apollo::cyber::Writer;
using apollo::cyber::Reader;
using apollo::cyber::Time;
using apollo::cyber::Node;
using apollo::drivers::Gps;
using apollo::drivers::Image;
using apollo::drivers::Imu;
using apollo::drivers::PCLPointCloud2Array;
using apollo::cyber::record::RecordReader;
using apollo::cyber::record::RecordViewer;
// reader
using GpsReaderPtr = std::shared_ptr<Reader<Gps>>;
using ImageReaderPtr = std::shared_ptr<Reader<Image>>;
using ImuReaderPtr = std::shared_ptr<Reader<Imu>>;
using PointCloud2ArrayReaderPtr = std::shared_ptr<Reader<PCLPointCloud2Array>>;
// writer
using PointCloud2ArrayWriterPtr = std::shared_ptr<Writer<PCLPointCloud2Array>>;
3. 在线或者离线播包读取数据
3.1. 类定义
class Scheduler {
public:
Scheduler();
~Scheduler();
void initialize(const std::vector<std::string>& params);
void run();
private:
void imuHandler(const std::shared_ptr<Imu>& msg);
void gpsHandler(const std::shared_ptr<Gps>& msg);
void cloudHandler(const std::shared_ptr<PCLPointCloud2Array>& msg);
private:
std::unique_ptr<Node> node_;
GpsReaderPtr gps_reader_;
PointCloud2ArrayReaderPtr cloud_reader_;
};
3.2. 初始化
void Scheduler::initialize() {
gps_reader_ = node_->CreateReader<Gps>("gps_topic", 5,
[this](const std::shared_ptr<Gps>& msg) {
this->gpsHandler(msg);
});
cloud_reader_ = node_->CreateReader<PCLPointCloud2Array>("cloud_topic", 5,
[this](const std::shared_ptr<PCLPointCloud2Array>& msg) {
this->cloudHandler(msg);
});
imu_reader_ = node_->CreateReader<Imu>("imu_topic", 10,
[this](const std::shared_ptr<Imu>& msg) {
this->imuHandler(msg);
});
}
3.3. 回调函数
void Scheduler::gpsHandler(const std::shared_ptr<Gps>& msg) {
double x = pose_msg->pos().x();
double y = pose_msg->pos().y();
double z = pose_msg->pos().z();
}
void Scheduler::cloudHandler(const std::shared_ptr<PCLPointCloud2Array>& msg) {
pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>);
adlab::common::util::fromProto<pcl::PointXYZI>(*(msg->mutable_clouds(0)), cloud->get()));
}
void Scheduler::imuHandler(const std::shared_ptr<Imu>& msg) {
double time = static_cast<double>(msg->utime()) * 1e-6;
// acceleration
const auto& acc = msg->linear_accel();
Eigen::Vector3d acceleration(acc.x(), acc.y(), acc.z());
// angular velocity
const auto& omega = msg->rotation_rate();
Eigen::Vector3d angular_velocity(omega.x(), omega.y(), omega.z());
}
3.4. 主函数
#include <stdlib.h>
#include <stdio.h>
DEFINE_string(configs, "configs.yaml", "");
int main(int argc, char** argv) {
google::ParseCommandLineFlags(&argc, &argv, true);
std::vector<std::string> arguments;
arguments.push_back(FLAGS_configs);
adlab::cyber::Init(argv[0]);
google::SetLogDestination(google::INFO, "");
ros::init(argc, argv, "node");
Scheduler schedular;
schedular.initialize(arguments);
adlab::cyber::Rate rate(10);
while (adlab::cyber::OK()) {
schedular.run();
rate.Sleep();
}
adlab::cyber::WaitForShutdown();
return 0;
}
4. 从包中直接读取数据
std::shared_ptr<RecordReader> record_reader_ptr = std::make_shared<RecordReader>(file_path);
std::set<std::string> channel_list = record_reader_ptr->GetChannelList();
std::shared_ptr<RecordViewer> recorder_viewer = std::make_shared<RecordViewer>(record_reader_ptr);
for (const auto& msg : *recorder_viewer) {
if (msg.channel_name == channel_name_) {
double time = msg.time;
Gps gps_msg;
gps_msg.ParseFromString(msg.content);
}
}
5. 常用命令
5.1. 播放记录
cyber_record play -f data
5.2. 显示记录信息
cyber_record info data