基于ROS下的安卓手机图像和IMU跑ORB-SLAM3

接之前文章,手上没有现成的单目+IMU硬件,但是安卓手机很普及。因此,本文讲下如何用手机跑ORB-SLAM3的Mono和Mono_Inertial。

1. 手机与PC通信

基于ROS下的信息发布和订阅,手机和PC在一个局域网下进行信息(image和IMU)传输。

手机APK参考了github上的2个开源Android_Camera-IMUandroid_ros_sensors,基于ros_java生成安卓APP,下载安装任一个APP到安卓手机,界面分别是这样:

手机和PC连一个无线网,如果没有无线网,用手机开一个热点,PC连热点也可以。

1)Ubuntu下roscore,启动ros。

2)ubuntu下ifconfig查看自己的IP,填入APP的localhost处(http://localhost:11311),第1张图是第一个APP,连无线网的IP,第2张图是第2个APP,连手机热点的IP。

3)rostopic list查看主题,发现图像是compressed,接入SLAM必须是raw才行,故进行republish:

rosrun image_transport republish compressed in:=/android/image_raw raw out:=/camera/image_raw

之后再看下rostopic list:

有了/camera/image_raw,此时OK了,你可以终端rostopic echo 对应主题 和rostopic hz 对应主题 查看信息是否OK和频率。

2 参数标定

跑单目+IMU效果好不好,最重要的是参数标定的准不准,参数包括:相机参数,IMU参数,相机和IMU的外参数,相机和IMU时间对齐的时间差。

相机参数可以通过ROS、opencv、matlab进行标定,IMU参数可以通过imu_utils进行标定,相机和IMU外参数可以通过kalibr或vins_mono在线标定,相机和IMU时间对齐的时间差可以通过vins_mono讲的或自己的代码标定,本文篇幅所限,后续如有时间再讲。

3 修改源码

在ros_mono_inertial.cc里修改。

1)修改订阅主题,在main函数里

ros::Subscriber sub_imu = n.subscribe("/android/imu", 2000, &ImuGrabber::GrabImu, &imugb);  //imu
ros::Subscriber sub_img0 = n.subscribe("/camera/image_raw", 100, &ImageGrabber::GrabImage,&igb);
std::thread sync_thread(&ImageGrabber::SyncWithImu,&igb);

2)如果是用第一个APP,IMU和相机的时间戳时间相差非常大,需要代码同步对齐,ImageGrabber::SyncWithImu函数里

if(!mpImuGb->imuBuf.empty())
            {
                // Load imu measurements from buffer
                vImuMeas.clear();
                static bool time_flag = true;
                static auto TIME_OFFSET = 0.0;
                if(time_flag){
                    TIME_OFFSET = mpImuGb->imuBuf.front()->header.stamp.toSec()-tIm;
                    time_flag = false;
                }
                //cout<<"imu_time: "<<setprecision(11)<<mpImuGb->imuBuf.front()->header.stamp.toSec()-TIME_OFFSET<<endl;
                //cout<<"image_time: "<<setprecision(11)<<tIm<<endl;
                while(!mpImuGb->imuBuf.empty() && mpImuGb->imuBuf.front()->header.stamp.toSec()-TIME_OFFSET<=tIm)
                {
                    double t = mpImuGb->imuBuf.front()->header.stamp.toSec() - TIME_OFFSET;
                    cv::Point3f acc(mpImuGb->imuBuf.front()->linear_acceleration.x, mpImuGb->imuBuf.front()->linear_acceleration.y, mpImuGb->imuBuf.front()->linear_acceleration.z);
                    cv::Point3f gyr(mpImuGb->imuBuf.front()->angular_velocity.x, mpImuGb->imuBuf.front()->angular_velocity.y, mpImuGb->imuBuf.front()->angular_velocity.z);
                    //cout<<"imudata: "<< t<<" "<<acc.x<<" "<<acc.y<<" "<<acc.z<<" "<<gyr.x<<" "<<gyr.y<<" "<<gyr.z<<endl;
                    vImuMeas.push_back(ORB_SLAM3::IMU::Point(acc,gyr,t));

                    mpImuGb->imuBuf.pop();
                }
            }

如果是用第二个APP,图像大小是1920*1080,需要进行resize和对应size下的图像参数标定。

4 跑ORB-SLAM3

按照ORB-SLAM3里的ros exsample的方法进行。

继续第一节的操作,首先/android/imu和/camera/image_raw数据都是OK的,之后

rosrun ORB_SLAM3 Mono_Inertial ORBvoc.bin ../../Monocular-Inertial/Mate10.yaml true

如果只跑单目,就是

rosrun ORB_SLAM3 Mono ORBvoc.bin ../../Monocular/Mate10.yaml

此时,就出来画面了,自己的参数一定要标好和微调,然后就根据轨迹效果实时的测试场景、优化算法吧。

### 配置 ORB-SLAM2 ORB-SLAM3 运行环境 要在 Ubuntu 20.04 上成功配置 ORB-SLAM2 ORB-SLAM3 并使其与 ROS 实现无缝集成,需遵循以下方法: #### 安装依赖项 首先安装必要的软件包工具链。这些包括编译器、构建工具以及 OpenCV 等库的支持。 ```bash sudo apt update && sudo apt upgrade -y sudo apt install build-essential cmake git libeigen3-dev libsuitesparse-dev \ libopencv-dev python3-catkin-tools ros-noetic-* -y ``` 上述命令会安装 CMake、Eigen 库、SuiteSparse 数学优化库、OpenCV 开发版本以及其他 ROS Noetic 所需的相关组件[^1]。 #### 下载并编译 ORB-SLAM2 ORB-SLAM3 克隆官方仓库到本地目录,并按照说明完成源码的下载与编译过程。 对于 **ORB-SLAM2**: ```bash git clone https://github.com/raulmur/ORB_SLAM2.git cd ORB_SLAM2 chmod +x build.sh ./build.sh ``` 而对于 **ORB-SLAM3**, 类似操作适用于此项目结构: ```bash git clone https://github.com/UZI-CVSLAB/orb_slam3_ros.git cd orb_slam3_ros/ catkin_make source devel/setup.bash ``` 注意,在此过程中可能遇到路径设置问题;确认最终生成可执行二进制文件位于指定位置 `PATH/ORB_SLAM3/Examples/ROS` 即表明正确无误。 #### 启动节点服务 为了验证整个系统的功能正常与否,可以开启多个终端窗口来分别启动不同的服务端口及数据流处理程序。 在一个新的 Terminal 中输入以下指令初始化核心通信框架: ```bash roscore ``` 接着于第二个 Tab 页面加载预先录制好的传感器数据集用于测试目的: ```bash rosbag play MH_01_easy.bag --clock ``` 最后一步是在第三个独立 Session 内调用实际算法逻辑模块本身: ```bash rosrun ORB_SLAM3 Mono Vocabulary/ORBvoc.txt Examples/Monocular/EuRoC.yaml ``` 以上三步共同协作实现了完整的视觉里程计解决方案演示效果展示[^2]。 通过这样的方式不仅完成了基础软硬件平台准备工作还确保了各子系统之间良好交互性能达到预期目标——即支持实时定位映射任务需求满足条件下的高效运作模式转换机制形成闭环控制体系架构设计思路清晰明确易于维护扩展性强等特点优势明显突出表现优异值得推广普及应用价值极高前景广阔未来潜力无限!
评论 16
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值