建购物网站怎么建呀,网站地址地图怎么做,公司网站建站软件,购物网站建设项目可研报告文章目录 0 引言1 安装依赖1.1 其他库安装1.2 pcl库安装 2 编译ORB-SLAM2_RGBD_DENSE_MAP2.1 build.sh2.2 build_ros.sh 3 运行ORB-SLAM2_RGBD_DENSE_MAP3.1 build.sh编译版本3.2 build_ros.sh编译版本 0 引言
ORB-SLAM2_RGBD_DENSE_MAP是基于ORB-SLAM2框架的一种RGB-D稠密地图… 文章目录 0 引言1 安装依赖1.1 其他库安装1.2 pcl库安装 2 编译ORB-SLAM2_RGBD_DENSE_MAP2.1 build.sh2.2 build_ros.sh 3 运行ORB-SLAM2_RGBD_DENSE_MAP3.1 build.sh编译版本3.2 build_ros.sh编译版本 0 引言
ORB-SLAM2_RGBD_DENSE_MAP是基于ORB-SLAM2框架的一种RGB-D稠密地图构建算法。ORB-SLAM2是一种基于单目、双目和RGB-D相机的实时定位与建图SLAM系统旨在通过计算机视觉技术实现机器人和自主驾驶汽车等设备的自主定位和地图构建。
ORB-SLAM2_RGBD_DENSE_MAP的主要思想是结合ORB-SLAM2框架的稠密重建算法和体素网格Voxel Grid滤波器对RGB-D相机采集到的图像数据进行处理从而得到一个稠密的3D点云表示进而构建出稠密的地图。该算法通过对相邻帧之间的视差图进行计算利用三角测量法估计相机到场景中每个像素的深度值并通过体素网格滤波器对深度图进行降采样从而减少计算量和存储空间。最终该算法可以生成一个具有高精度和高分辨率的稠密地图。
ORB-SLAM2_RGBD_DENSE_MAP算法的优点是具有较高的重建精度和鲁棒性在各种环境和光照条件下均表现良好。然而由于该算法需要进行大量的计算和存储因此它的实时性和运行效率可能受到一定的影响。
本文系统环境
Ubuntu18.04ROS-melodicOpenCV3.2.0Eigen 3.3.4Pangolin-0.6PCL 1.8.1realsense-ros (若用硬件D435i)
1 安装依赖
1.1 其他库安装
ORB-SLAM2算法1已针对Ubuntu20.04安装ORB-SLAM2所需的依赖库安装 OpenCVEigenPangolin 可以参考下。
1.2 pcl库安装
但ORB-SLAM2_RGBD_DENSE_MAP 因为是稠密建图还需要安装pcl1.7以上版本本文是安装了pcl1.8大版本可先下载 pcl 1.8.1 版本点击Source code(zip
先安装pcl1.8.1所需的依赖库
sudo apt-get update
sudo apt-get install git build-essential linux-libc-dev
sudo apt-get install cmake cmake-gui
sudo apt-get install libusb-1.0-0-dev libusb-dev libudev-dev
sudo apt-get install mpi-default-dev openmpi-bin openmpi-common
sudo apt-get install libflann1.9 libflann-dev
sudo apt-get install libeigen3-dev
sudo apt-get install libboost-all-dev
sudo apt-get install libvtk7.1-qt libvtk7.1
sudo apt-get install libqhull* libgtest-dev
sudo apt-get install freeglut3-dev pkg-config
sudo apt-get install libxmu-dev libxi-dev
sudo apt-get install mono-complete
sudo apt-get install openjdk-8-jdk openjdk-8-jre然后解压下载的pcl1.8.1源码并进入到pcl1.8.1文件夹中
mkdir build
cd build
cmake ..
make -j4
sudo make install测试pcl是否安装成功的话可用pcl_viewer xxx.pcd如果没有pcd文件可去点云库PCL(Point Cloud Library)的学习资源汇总下载rabbit.pcd
pcl_viewer rabbit.pcd2 编译ORB-SLAM2_RGBD_DENSE_MAP
编译类似ORB-SLAM2的安装但可能会出现不一样的问题。首先下载ORB-SLAM2_RGBD_DENSE_MAP
git clone https://github.com/xiaobainixi/ORB-SLAM2_RGBD_DENSE_MAP.git由于安装的是pcl1.8首先将CMakeLists.txt中find_package( PCL 1.7 REQUIRED )改成了find_package( PCL 1.8 REQUIRED )
2.1 build.sh
# 下载的ORB-SLAM2_RGBD_DENSE_MAP工程目录下
chmod x build.sh
./build.shtips: ./build.sh build_log.txt 21 可打印整个编译log到文件
编译问题1
make: *** [all] Error 1
Converting vocabulary to binary
./build.sh: line 30: ./tools/bin_vocabulary: Permission denied
原因是./tools/bin_vocabulary 词袋文件没有执行权限如下给其权限
# ORB-SLAM2_RGBD_DENSE_MAP 目录下执行
sudo chmod x tools/bin_vocabulary编译问题2
../Thirdparty/DBoW2/lib/libDBoW2.so: undefined reference to cv::_OutputArray::_OutputArray(cv::Mat)
collect2: error: ld returned 1 exit status
CMakeFiles/rgbd_tum.dir/build.make:391: recipe for target ../bin/rgbd_tum failed
make[2]: *** [../bin/rgbd_tum] Error 1
CMakeFiles/Makefile2:124: recipe for target CMakeFiles/rgbd_tum.dir/all failed
make[1]: *** [CMakeFiles/rgbd_tum.dir/all] Error 2
Makefile:90: recipe for target all failed
make: *** [all] Error 2
Converting vocabulary to binary
./tools/bin_vocabulary: error while loading shared libraries: libopencv_core3.so.3.3: cannot open shared object file: No such file or directory
Error1一开始以为OpenCV的问题但后来排查到我这个是由于之前尝试编译时第三方库DBoW2和g2o没有完全编译删除两个第三方库中的build文件夹重新编译即可。
Error2 是tools中的bin_vocabulary词袋找不到libopencv_core3.so.3.3而且ORB-SLAM2_RGBD_DENSE_MAP的lib也没有该版本的opencv动态链接库而本文系统安装的是OpenCV 3.2.0版本也不符合所以临时解决办法是不用bin_vocabulary词袋可执行文件改用ORB-SLAM2工程中的词袋文件ORBvoc.txt
# 首先注释掉 build.sh 中的bin_vocabulary部分
# 最后几行注释掉# cd ..
# echo Converting vocabulary to binary
# ./tools/bin_vocabulary最后复制ORB-SLAM2中的词袋文件夹Vocabulary到ORB-SLAM2_RGBD_DENSE_MAP工程目录下。
重新编译即可编译成功
/usr/include/eigen3/Eigen/src/Core/util/Constants.h:162:37: note: declared hereEIGEN_DEPRECATED const unsigned int AlignedBit 0x80;^~~~~~~~~~
[ 94%] Linking CXX executable ../bin/mono_tum
[ 97%] Linking CXX executable ../bin/mono_kitti
[100%] Linking CXX executable ../bin/mono_euroc
[100%] Built target mono_tum
[100%] Built target mono_kitti
[100%] Built target mono_euroc2.2 build_ros.sh
首先添加该工程到ROS_PACKAGE_PATH
gedit ~/.bashrc
# 最后一行新增,其中冒号后的PATH是自己ORB-SLAM2_RGBD_DENSE_MAP工程存放目录
export ROS_PACKAGE_PATH${ROS_PACKAGE_PATH}:PATH/ORB-SLAM2_RGBD_DENSE_MAP/Examples/ROS
# 保存后source
source ~/.bashrc然后执行如下命令进行编译
# 下载的ORB-SLAM2_RGBD_DENSE_MAP工程目录下
chmod x build_ros.sh
./build_ros.sh3 运行ORB-SLAM2_RGBD_DENSE_MAP
3.1 build.sh编译版本
由于用到rgb和depth图所以参考ORB-SLAM2算法2下载TUM的rgbd_dataset_freiburg1_desk数据集准备好数据集后可执行以下命令其中PATH是rgbd_dataset_freiburg1_desk文件夹的存放目录
# 下载的ORB-SLAM2_RGBD_DENSE_MAP工程目录下
./bin/rgbd_tum Vocabulary/ORBvoc.txt Examples/RGB-D/TUM1.yaml PATH/rgbd_dataset_freiburg1_desk PATH/rgbd_dataset_freiburg1_desk/associations.txt运行问题1
Depth Threshold (Close/Far Points): 3.09294-------
Start processing sequence ...
Images in the sequence: 573New map created with 945 points
Segmentation fault (core dumped)这种 段错误(核心已转储)的问题本文暂未完全解决如有欢迎分享交流先用以下的临时解决办法(该问题仍会偶发):
在 CMakeLists.txt 和 Thirdparty/g2o/CMakeLists.txt中删除-marchnative
# set(CMAKE_C_FLAGS ${CMAKE_C_FLAGS} -Wall -O3 -marchnative )
# set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall -O3 -marchnative)set(CMAKE_C_FLAGS ${CMAKE_C_FLAGS} -Wall -O3)
set(CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS} -Wall -O3)在有定义Eigen的头文件中添加预编译命令EIGEN_MAKE_ALIGNED_OPERATOR_NEW 分别是include路径下Converter.h、LoopClosing.h、PointCloude.h这三个文件 Converter.h
class Converter
{public:# 添加预编译命令EIGEN_MAKE_ALIGNED_OPERATOR_NEWstatic std::vectorcv::Mat toDescriptorVector(const cv::Mat Descriptors);static g2o::SE3Quat toSE3Quat(const cv::Mat cvT);static g2o::SE3Quat toSE3Quat(const g2o::Sim3 gSim3);LoopClosing.h两次修改第一个public中添加第二个public中的注释掉
class LoopClosing
{public:# 添加预编译命令EIGEN_MAKE_ALIGNED_OPERATOR_NEWtypedef pairsetKeyFrame*,int ConsistentGroup;typedef mapKeyFrame*,g2o::Sim3,std::lessKeyFrame*,Eigen::aligned_allocatorstd::pairconst KeyFrame*, g2o::Sim3 KeyFrameAndPose;public:LoopClosing(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale, shared_ptrPointCloudMapping pPointCloud);void SetTracker(Tracking* pTracker);void SetLocalMapper(LocalMapping* pLocalMapper);// Main functionvoid Run();void InsertKeyFrame(KeyFrame *pKF);void RequestReset();// This function will run in a separate threadvoid RunGlobalBundleAdjustment(unsigned long nLoopKF);shared_ptrPointCloudMapping mpPointCloudMapping;bool isRunningGBA(){unique_lockstd::mutex lock(mMutexGBA);return mbRunningGBA;}bool isFinishedGBA(){unique_lockstd::mutex lock(mMutexGBA);return mbFinishedGBA;}void RequestFinish();bool isFinished();# 注释掉预编译命令// EIGEN_MAKE_ALIGNED_OPERATOR_NEWint loopcount 0;PointCloude.h
class PointCloude
{typedef pcl::PointXYZRGBA PointT;typedef pcl::PointCloudPointT PointCloud;
public:PointCloud::Ptr pcE;
public:# 添加预编译命令EIGEN_MAKE_ALIGNED_OPERATOR_NEWEigen::Isometry3d T;int pcID;运行问题2
viewer视图中没有点云只有坐标系改动include文件夹中的 pointcloudmapping.h头文件
# bool loopbusy;
bool loopbusy false;
运行问题3 确认TUM1.yaml文件里有没有点云地图的参数如果没有就把以下几行加在最后面
PointCloudMapping.Resolution: 0.01
meank: 50
thresh: 2.0
重新执行./build.sh编译完成后重新执行
# 下载的ORB-SLAM2_RGBD_DENSE_MAP工程目录下
./bin/rgbd_tum Vocabulary/ORBvoc.txt Examples/RGB-D/TUM1.yaml PATH/rgbd_dataset_freiburg1_desk PATH/rgbd_dataset_freiburg1_desk/associations.txt运行结果
median tracking time: 0.0200984
mean tracking time: 0.0206714Saving camera trajectory to CameraTrajectory1.txt ...trajectory saved!Saving keyframe trajectory to CameraTrajectory2.txt ...trajectory saved!
globalMap save finishedCurrent Frame 关键帧可视化界面 Map Viewer 轨迹地图可视化界面 viewer 稠密地图可视化界面 保存的稠密地图文件result.pcd可用已安装的pcl打开 pcl_viewer result.pcd 至此成功用TUM数据包运行非ROS版本的ORB-SLAM2_RGBD_DENSE_MAP并可视化生成的稠密地图。
3.2 build_ros.sh编译版本
本文这里就不用TUM的开源数据测试了因为恰好有D435i相机可以实时发出深度图和rgb图来测试(录制的一小段数据ORB-SLAM2-RGBD-DENSE-MAP-data.tar)所以以下就是以此为例。
默认已经安装realsense-ros的相机驱动首先是相机启动文件(rs_camera.launch)的配置保证发出与rgb图对齐的深度图false修改成true arg nameenable_depth defaulttrue/然后插上D435i相机后USB3.0新开终端启动D435i相机
# source 激活realsense-ros的相机驱动后执行
roslaunch realsense2_camera rs_camera.launch启动后通过rostopic list可查的所需的rgb图和对齐的深度图的topic
# 与rgb图对齐的深度图
/camera/aligned_depth_to_color/image_raw
# rgb图
/camera/color/image_raw然后修改代码中的两个topic在ORB-SLAM2_RGBD_DENSE_MAP/Examples/ROS/ORB_SLAM21/src/ros_rgbd.cc文件中修改 // message_filters::Subscribersensor_msgs::Image rgb_sub(nh, /kinect2/qhd/image_color_rect, 1);// message_filters::Subscribersensor_msgs::Image depth_sub(nh, /kinect2/qhd/image_depth_rect, 1);message_filters::Subscribersensor_msgs::Image rgb_sub(nh, /camera/color/image_raw, 1);message_filters::Subscribersensor_msgs::Image depth_sub(nh, /camera/aligned_depth_to_color/image_raw, 1);当然还有对应的配置文件在ORB-SLAM2_RGBD_DENSE_MAP/Examples/ROS/ORB_SLAM21/目录下新建配置文件d435i.yaml主要是fx, fy, cx, cy、分辨率帧率baseline等要修改成所用的D435i相机对应的好在D435i相机发出的rgb图已经是去畸变的而且给出了内参可通过rostopic echo /camera/color/camera_info命令查询具体如下
查询结果其中K即是所需的内参
header: seq: 0stamp: secs: 1691576284nsecs: 247732162frame_id: camera_color_optical_frame
height: 540
width: 960
distortion_model: plumb_bob
D: [0.0, 0.0, 0.0, 0.0, 0.0]
K: [682.6236572265625, 0.0, 490.54339599609375, 0.0, 682.521240234375, 275.81976318359375, 0.0, 0.0,
1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [682.6236572265625, 0.0, 490.54339599609375, 0.0, 0.0, 682.521240234375, 275.81976318359375, 0.0,
0.0, 0.0, 1.0, 0.0]d435i.yaml配置文件信息
%YAML:1.0#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 682.6236572265625
Camera.fy: 682.521240234375
Camera.cx: 490.54339599609375
Camera.cy: 275.81976318359375Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.p3: 0.0Camera.width: 960
Camera.height: 540
# Camera frames per second
Camera.fps: 15.0# IR projector baseline times fx (aprox.)
# bf baseline (in meters) * fx, D435i的 baseline 50 mm
Camera.bf: 50.0# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1# Close/Far threshold. Baseline times.
ThDepth: 40.0# Deptmap values factor
DepthMapFactor: 1000.0#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize:2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500PointCloudMapping.Resolution: 0.01
meank: 50
thresh: 2.0
然后重新执行./build_ros.sh编译编译成功后执行如下命令运行
# ORB-SLAM2_RGBD_DENSE_MAP 目录下执行
rosrun ORB_SLAM21 RGBD Vocabulary/ORBvoc.txt Examples/ROS/ORB_SLAM21/d435i.yaml运行后相比原版的ORB-SLAM2多生成一个viewer的稠密建图的可视化界面
Current Frame可视化界面 Map Viewer可视化界面 viewer可视化界面 至此成功用在线加载D435i相机发出的rgb图和对齐的深度图运行ROS版本的ORB-SLAM2_RGBD_DENSE_MAP并可视化生成的稠密地图。
Reference:
ORB-SLAM2_RGBD_DENSE_MAPORB-SLAM2算法1之Ubuntu20.04ROS-noetic安装ORB-SLAM2及各种问题解决点云库PCL(Point Cloud Library)的学习资源汇总ORB-SLAM2算法2之TUM开源数据运行ORB-SLAM2生成轨迹并用evo工具评估轨迹ORB-SLAM2-RGBD-DENSE-MAP-data.tar 须知少时凌云志曾许人间第一流。 ⭐️