这是楼主自己的毕设需要看的文件,所以写一下自己的阅读心得,哈哈哈发现有问题提出来大家一起解决
ORB-SLAM2将自己编写的源文件封装成API库文件,使用ORB::SLAM2为命名空间
1. 编译的节点文件ros_rgbd.cc
主要作用:
- 初始化SLAM系统,声明与定义消息回调函数——回调函数的主要作用:将ROS机制中的消息转换为OPENCV格式下的Mat(ROS::cv_bridge),在将图片矩阵传递给局部跟踪线程(Track)
// 声明类(图像收集类)
class ImageGrabber
{
public:
ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){
} //构造函数的申明与定义(申明一个指针)——C++函数后面跟:表示赋值
void GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD); //ROS中的消息机制——&设置引用参数,在局部变量的变化会引起实参的变化
ORB_SLAM2::System* mpSLAM; //函数成员变量,初始化SLAM系统
};
//消息回调函数
// 定义消息回调函数(输入为两个消息常量)
// 将消息转换为opencv下的矩阵类型
// 传入消息常量
void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD) //引用参数
{
// Copy the ros image message to cv::Mat.利用CV:bridge连接不同的数据类型
cv_bridge::CvImageConstPtr cv_ptrRGB; //将sonsor::message转换为cv::message
try
{
cv_ptrRGB = cv_bridge::toCvShare(msgRGB); // 函数返回cv状态下的常量值(返回封装后的一个类)
}
catch (cv_bridge::Exception& e) //很少以直接变量传送入函数中
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
cv_bridge::CvImageConstPtr cv_ptrD;
try
{
cv_ptrD = cv_bridge::toCvShare(msgD);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
//开始进入跟踪线程
mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image