接着上一篇,完成上一篇配置后继续:
1、Kinect驱动安装,不多说
2、cd到程序根目录,添加build_ros.sh文件,内容如下:
echo "Building ROS nodes"
cd Examples/ROS/ORB_SLAM2
mkdir build
cd build
cmake .. -DROS_BUILD_TYPE=Release
make -j
然后将 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so 和 /usr/lib/x86_64-linux-gnu/libboost_system.so ,/usr/local/lib/libopencv_core.so (libopencv_core3.so)拷贝到根目录的lib文件夹下。
CMakeLists.txt修改如下:
cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
rosbuild_init()
IF(NOT ROS_BUILD_TYPE)
SET(ROS_BUILD_TYPE Release)
ENDIF()
MESSAGE("Build type: " ${ROS_BUILD_TYPE})
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
# Check C++11 or C++0x support
include(CheckCXXCompilerFlag)
CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
if(COMPILER_SUPPORTS_CXX11)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
add_definitions(-DCOMPILEDWITHC11)
message(STATUS "Using flag -std=c++11.")
elseif(COMPILER_SUPPORTS_CXX0X)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
add_definitions(-DCOMPILEDWITHC0X)
message(STATUS "Using flag -std=c++0x.")
else()
message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
endif()
LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules)
find_package(OpenCV REQUIRED)
find_package(G2O REQUIRED) ####
find_package(Eigen3 REQUIRED)
find_package(Pangolin REQUIRED)
find_package( PCL REQUIRED ) ###
include_directories(
${PROJECT_SOURCE_DIR}
${PROJECT_SOURCE_DIR}/../../../
${PROJECT_SOURCE_DIR}/../../../include
${Pangolin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS} ###
)
add_definitions( ${PCL_DEFINITIONS} ) ###
link_directories( ${PCL_LIBRARY_DIRS} ) ###
set(LIBS
${OpenCV_LIBS}
${EIGEN3_LIBS}
${Pangolin_LIBRARIES}
${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so
g2o_core g2o_types_slam3d g2o_solver_csparse g2o_stuff g2o_csparse_extension g2o_types_sim3 g2o_types_sba
${PCL_LIBRARIES}
${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so
# ${PROJECT_SOURCE_DIR}/../../../lib/libboost_filesystem.so
# ${PROJECT_SOURCE_DIR}/../../../lib/libboost_system.so
# ${PROJECT_SOURCE_DIR}/../../../lib/libopencv_core.so ###
)
# Node for monocular camera
rosbuild_add_executable(Mono
src/ros_mono.cc
)
target_link_libraries(Mono
${LIBS}
)
# Node for RGB-D camera
rosbuild_add_executable(RGBD
src/ros_rgbd.cc
)
target_link_libraries(RGBD
${LIBS}
)
然后,
sudo gedit Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc
做如下修改:
message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/kinect2/hd/image_color", 1);
message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "/kinect2/hd/image_depth_rect", 1);
然后在根目录下添加kinect标定配置文件 kinect2.yaml,我的内容如下:
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 1.0463505828017596e+03
Camera.fy: 1.0437078414277514e+03
Camera.cx: 9.5816557284218459e+02
Camera.cy: 5.4111840298331435e+02
Camera.k1: 3.4696500016314420e-02
Camera.k2: -2.5306047171647417e-02
Camera.p1: 1.6317902928695393e-03
Camera.p2: 1.1387356663988056e-03
Camera.k3: -1.2753435167343403e-02
Camera.width: 1920
Camera.height: 1080
# Camera frames per second
Camera.fps: 30.0
# IR projector baseline times fx (aprox.)
Camera.bf: 40.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: 50.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: 500
#--------------------------------------------------------------------------------------------
# PointCloud Mapping
#--------------------------------------------------------------------------------------------
PointCloudMapping.Resolution: 0.03
最后,
chmod +x build_ros.sh
./build_ros.sh
运行:
新开一个终端:
roslaunch kinect2_bridge kinect2_bridge.launch
cd到程序根目录下:
rosrun ORB_SLAM2_with_pointcloud RGBD Vocabulary/ORBvoc.txt kinect2.yaml