Jetson Nano + ROS + 乐视体感相机视觉 SLAM

最近更新于 2024-05-05 14:18

测试环境:

Jetson Nano - JP 4.6 (Ubuntu 18.04 arm64)
乐视三合一体感摄像头 LeTMC-520(对等 Orbbec 3D Astra Pro 相机)

1.安装 ROS,照着官方教程走就行:http://wiki.ros.org/cn/melodic/Installation/Ubuntu(安装桌面完整版)

2.安装相机驱动 astra_camera_ros,跟着项目主页的说明操作:https://github.com/orbbec/ros_astra_camera

Table of Contents

点云图

1.编辑配置文件

将相机插到 Jetson Nano上,执行命令查询设备号

lsusb

502 是彩色相机(记住),403 是深度相机

编辑 ~/catkin_ws/src/ros_astra_camera/launch/astrapro.launch,找到 name=”product” 的位置,将 value 改为上面查询到的彩色相机的设备号

然后创建点云图配置文件

mkdir -p ~/catkin_ws/src/rviz
touch ~/catkin_ws/src/rviz/depth_camera.rviz

编辑 ~/catkin_ws/src/rviz/depth_camera.rviz,写入如下内容

Panels:
  - Class: rviz/Displays
    Help Height: 88
    Name: Displays
    Property Tree Widget:
      Expanded:
        - /Global Options1
        - /Status1
        - /Grid1
        - /PointCloud21
      Splitter Ratio: 0.5
    Tree Height: 453
  - Class: rviz/Selection
    Name: Selection
  - Class: rviz/Tool Properties
    Expanded:
      - /2D Pose Estimate1
      - /2D Nav Goal1
      - /Publish Point1
    Name: Tool Properties
    Splitter Ratio: 0.588679016
  - Class: rviz/Views
    Expanded:
      - /Current View1
    Name: Views
    Splitter Ratio: 0.5
  - Class: rviz/Time
    Experimental: false
    Name: Time
    SyncMode: 0
    SyncSource: PointCloud2
Visualization Manager:
  Class: ""
  Displays:
    - Alpha: 0.5
      Cell Size: 1
      Class: rviz/Grid
      Color: 159; 147; 147
      Enabled: true
      Line Style:
        Line Width: 0.0299999993
        Value: Lines
      Name: Grid
      Normal Cell Count: 0
      Offset:
        X: 0
        Y: 0
        Z: 0
      Plane: XZ
      Plane Cell Count: 10
      Reference Frame: camera_depth_optical_frame
      Value: true
    - Alpha: 1
      Autocompute Intensity Bounds: true
      Autocompute Value Bounds:
        Max Value: 8.875
        Min Value: 1.28500009
        Value: true
      Axis: X
      Channel Name: intensity
      Class: rviz/PointCloud2
      Color: 255; 255; 255
      Color Transformer: AxisColor
      Decay Time: 0
      Enabled: true
      Invert Rainbow: false
      Max Color: 255; 255; 255
      Max Intensity: 4096
      Min Color: 0; 0; 0
      Min Intensity: 0
      Name: PointCloud2
      Position Transformer: XYZ
      Queue Size: 10
      Selectable: true
      Size (Pixels): 3
      Size (m): 0.00999999978
      Style: Squares
      Topic: /camera/depth/points
      Unreliable: false
      Use Fixed Frame: true
      Use rainbow: true
      Value: true
  Enabled: true
  Global Options:
    Background Color: 48; 48; 48
    Default Light: true
    Fixed Frame: camera_depth_frame
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz/Interact
      Hide Inactive Objects: true
    - Class: rviz/MoveCamera
    - Class: rviz/Select
    - Class: rviz/FocusCamera
    - Class: rviz/Measure
    - Class: rviz/SetInitialPose
      Topic: /initialpose
    - Class: rviz/SetGoal
      Topic: /move_base_simple/goal
    - Class: rviz/PublishPoint
      Single click: true
      Topic: /clicked_point
  Value: true
  Views:
    Current:
      Class: rviz/Orbit
      Distance: 7.51409006
      Enable Stereo Rendering:
        Stereo Eye Separation: 0.0599999987
        Stereo Focal Distance: 1
        Swap Stereo Eyes: false
        Value: false
      Focal Point:
        X: 2.80641723
        Y: -0.0263374168
        Z: -0.295807391
      Focal Shape Fixed Size: true
      Focal Shape Size: 0.0500000007
      Invert Z Axis: false
      Name: Current View
      Near Clip Distance: 0.00999999978
      Pitch: 0.305203468
      Target Frame: <Fixed Frame>
      Value: Orbit (rviz)
      Yaw: 3.89040422
    Saved: ~
Window Geometry:
  Displays:
    collapsed: false
  Height: 744
  Hide Left Dock: false
  Hide Right Dock: true
  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000025efc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000025e000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006500000001a9000001430000000000000000000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002c4000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005150000003efc0100000002fb0000000800540069006d00650100000000000005150000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a50000025e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
  Selection:
    collapsed: false
  Time:
    collapsed: false
  Tool Properties:
    collapsed: false
  Views:
    collapsed: true
  Width: 1301
  X: 65
  Y: 24

2.查看点云图

启动相机

# 刷新环境
echo "source ~/catkin_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

# 启动
roslaunch astra_camera astrapro.launch

另外打开一个终端启动 rviz

rosrun rviz rviz -d /home/yx/catkin_ws/src/rviz/depth_camera.rviz

现在显示的就是扫描的点云图(深度相机采集的数据),这里再添加一下彩色相机图

SLAM

注:准备好科学上网

1.安装依赖

安装 OpenCV 3.2.0

sudo apt install -y libavcodec-dev libavformat-dev libswscale-dev libv4l-dev libxvidcore-dev libx264-dev libatlas-base-dev gfortran libgtk2.0-dev libjpeg-dev libpng-dev libgtk-3-dev libdc1394-22-dev libtesseract-dev libtiff-dev libatlas-base-dev libdw-dev libunwind-dev libgmp-dev libgsl-dev libgslcblas0 flex bison libgst-dev libcap-dev build-essential cmake git pkg-config ffmpeg libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libvulkan-dev libvulkan1 mesa-vulkan-drivers

cd ~/catkin_ws/src

git clone https://github.com/opencv/opencv.git --branch 3.2.0 --depth=1

cd oepncv

git clone https://github.com/opencv/opencv_contrib.git --branch 3.2.0 --depth=1

### 以 root 权限编辑 /usr/include/c++/7/cstdlib,在 75 行找到 “#include_next <stdlib.h>”,改为 “#include <stdlib.h>”

### 以 root 权限编辑 /usr/include/c++/7/bits/std_abs.h,在 38 行找到 “#include_next <stdlib.h>”,改为 “#include <stdlib.h>”

### 以 root 权限编辑 /usr/include/c++/7/cmath,在 45 行找到 “#include_next <math.h>”,改为 “#include <math.h>”

mkdir build && cd build

cmake -DCMAKE_BUILD_TYPE=RELEASE -DBUILD_opencv_python2=ON -DBUILD_opencv_python3=ON -DOPENCV_ENABLE_NONFREE=ON -DBUILD_TESTS=OFF -DBUILD_FAT_JAVA_LIB=OFF -DBUILD_EXAMPLES=OFF -DOPENCV_EXTRA_MODULES_PATH=../opencv_contrib/modules -DOPENCV_GENERATE_PKGCONFIG=ON -DWITH_CUDA=OFF ..

sudo make install -j4

安装 Pangolin 0.8

cd ~/catkin_ws/src

git clone --recursive https://github.com/stevenlovegrove/Pangolin.git  --depth=1 --branch=v0.8

cd Pangolin

./scripts/install_prerequisites.sh recommended

mkdir build && cd build

cmake ..

make -j4

安装其它依赖

sudo apt install -y libeigen3-dev

2.安装 ORB_SLAM3

cd ~/catkin_ws/src

git clone https://github.com/UZ-SLAMLab/ORB_SLAM3.git --depth=1 --branch=v1.0-release

cd ORB_SLAM3

### 编辑 build.sh,凡是出现 “make -j” 的地方都替换为 “make -j1”,避免内存不够且因为占用过高被系统杀死。(不建议加交换分区,Jetson Nano 的“磁盘”是外置内存卡,把内存虚拟在内存卡上速度慢得要命,不如降低编译线程,说不定更快)

### 编辑 CMakeLists.txt,找到 “find_package(OpenCV 4.4)”,改为 “find_package(OpenCV 3.2)”

./build.sh

cd Examples_old/ROS/ORB_SLAM3

### 编辑 CMakeLists.txt,找到 “find_package(OpenCV 3.0 QUIET)” 改为 “find_package(OpenCV 3.2 QUIET)”

### 编辑 src/AR/ros_mono_ar.cc,找到 151 行的 “cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());” 改为:
“
cv::Mat Tcw;
Sophus::SE3f Tcw_SE3f = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
Eigen::Matrix4f Tcw_Matrix = Tcw_SE3f.matrix();
cv::eigen2cv(Tcw_Matrix, Tcw);
”
然后在开头引入头文件的地方添加包含下面两个头文件:
“
#include <Eigen/Dense>
#include <opencv2/core/eigen.hpp>
”

### 编辑 src/AR/ViewerAR.cc,在 530 行找到 “cv::Mat Xw = pMP->GetWorldPos();”,改为:
“
cv::Mat Xw;
cv::eigen2cv(pMP->GetWorldPos(), Xw);
”
然后在开头引入头文件的地方添加包含下面两个头文件:
“
#include <Eigen/Dense>
#include <opencv2/core/eigen.hpp>
”
在 407 行左右的位置找到 
“
vPoints.push_back(pMP->GetWorldPos());
vPointMP.push_back(pMP);
”,改为:
“
cv::Mat WorldPos;
cv::eigen2cv(pMP->GetWorldPos(), WorldPos);
vPoints.push_back(WorldPos);
”

mkdir -p build && cd build

cmake ..

make

3.运行 SLAM 程序

# 打开一个终端执行命令启动相机
roslaunch astra_camera astrapro.launch

# 再打开一个终端运行 SLAM 程序
rosrun ORB_SLAM3 RGBD ~/catkin_ws/src/ORB_SLAM3/Vocabulary/ORBvoc.txt ~/catkin_ws/src/ORB_SLAM3/Examples_old/ROS/ORB_SLAM3/Asus.yaml 
Jetson Nano + ROS + 乐视体感相机视觉 SLAM
Scroll to top