该ros包需要配合我们修改过的ORB-SLAM2进行使用(使用分支V1.0.0),由ORB-SLAM2或者其他的位姿估计节点输出相机的位姿,该节点接受彩色图与深度图生成点云,根据位姿估计器输出的相机位姿Tcw对局部点云进行拼接。
详细的教程请参考csdn博客系列教程:ORB-SLAM2 在线构建稠密点云
使用说明
git clone https://github.com/RuPingCen/pointcloud_mapping.git
roslaunch pointcloud_mapping pointcloud_mapping.launch
- clone the pose estimater node (This is an extended ORB-SLAM2 system)
cd catkin_ws/src
git clone https://github.com/RuPingCen/ORB-SLAM2.git
cd ORB_SLAM2
./build.sh
./build_ros.sh
- clone the mapping node and elas lib
note: the elas-lib is used for calculate the disparity from the stereo camera
cd catkin_ws/src
git clone https://github.com/RuPingCen/pointcloud_mapping.git
git clone https://github.com/jeffdelmerico/cyphy-elas-ros.git
- build workspace
cd catkin_ws
catkin_make
- download the TUM rosbag form the website, then open a terminal and play the rosbag
rosbag play rgbd_dataset_freiburg1_room.bag
- launch the pose estimator
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:/YOUR-PATH/ORB_SLAM2/Examples/ROS
rosrun ORB_SLAM2 astra Vocabulary/ORBvoc.txt Examples/ROS/ORB_SLAM2/TUM1_ROSbag.yaml
- launch the mapping node with launch file
cd catkin_ws/src
source devel/setup.bash
roslaunch pointcloud_mapping tum1.launch
- download the KITTI images form the website, then the python script is used to convert the images to rosbag.
roslaunch publish_image_datasets publish_kitti.launch
- launch the pose estimator
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:/YOUR-PATH/ORB_SLAM2/Examples/ROS
rosrun ORB_SLAM2 Stereo Vocabulary/ORBvoc.txt Examples/Stereo/KITTI00-02.yaml false
- launch the mapping node with launch file
cd catkin_ws/src
source devel/setup.bash
roslaunch elas_ros kitti_no_rviz.launch
roslaunch pointcloud_mapping kitti.launch
This is a demo on KITTI dataset demo STEREO
The Mick is a home-made diff-wheeled car, equipped with ZED binocular camera.
This is a demo on Mick demo STEREO