拿到全新的Jetson Orin-NX开发板时,第一件事就是释放它的全部性能潜力。这块搭载ARM架构的板卡默认运行在节能模式,我们需要手动开启最大性能模式。在系统右上角的电源菜单里选择"0:MAXN"模式,这个操作相当于给汽车挂上了S档,编译速度能提升3倍以上。
我建议先安装jetson-stats工具来监控硬件状态:
bash复制sudo apt-get update
sudo apt-get install python3-pip
sudo pip3 install -U jetson-stats
安装后运行jtop命令,你会看到一个酷似htop的监控界面,这里可以实时查看CPU/GPU频率、内存占用和温度。特别要注意的是,Orin-NX的CUDA核心数比前代Xavier多了一倍,但默认频率比较保守,在持续高负载时可能会降频。
选择CUDA 11.4版本不是随意决定的,经过实测发现这是目前对Orin-NX兼容性最好的版本。安装前先用jetson_release命令检查现有环境,如果预装了其他版本CUDA,建议彻底卸载:
bash复制sudo apt-get --purge remove "*cublas*" "*cufft*" "*curand*" \
"*cusolver*" "*cusparse*" "*npp*" "*nvjpeg*" "cuda*" "nsight*"
安装CUDA 11.4的核心命令很简单:
bash复制sudo apt-get install cuda-11-4
但这里有个坑我踩过三次——必须同步安装配套的cuDNN:
bash复制sudo apt-get install libcudnn8
安装完成后,需要处理一个ARM架构特有的OpenGL兼容问题。编辑CUDA头文件:
bash复制sudo vim /usr/local/cuda/include/cuda_gl_interop.h
找到62-68行,按照以下方式注释(保留绿色部分):
c复制//#if defined(__arm__) || defined(__aarch64__)
//#ifndef GL_VERSION
//#error Please include the appropriate gl headers before including cuda_gl_interop.h
//#endif
//#else
#include <GL/gl.h>
//#endif
Orin-NX对OpenCV 4.x的支持确实不够完善,经过多次测试,3.4.18版本是最稳定的选择。但官方源里的OpenCV不带CUDA支持,必须从源码编译。
首先清理可能存在的旧版本:
bash复制sudo apt-get purge libopencv*
sudo apt autoremove
sudo rm -rf /usr/include/opencv*
下载指定版本源码时,建议同时下载contrib模块:
bash复制cd ~/Downloads
wget -O opencv.zip https://github.com/opencv/opencv/archive/3.4.18.zip
wget -O contrib.zip https://github.com/opencv/opencv_contrib/archive/3.4.18.zip
编译参数中最关键的是CUDA_ARCH_BIN设置,Orin-NX对应的计算能力是8.7:
bash复制cmake -D CMAKE_BUILD_TYPE=RELEASE \
-D CMAKE_INSTALL_PREFIX=/usr/local \
-D WITH_CUDA=ON \
-D CUDA_ARCH_BIN=8.7 \
-D CUDA_ARCH_PTX="" \
-D ENABLE_FAST_MATH=ON \
-D CUDA_FAST_MATH=ON \
-D WITH_CUBLAS=ON \
-D OPENCV_EXTRA_MODULES_PATH=../opencv_contrib-3.4.18/modules \
..
make时建议使用-j$(nproc)参数自动匹配核心数,整个过程大约需要2小时。完成后务必检查CUDA支持是否生效:
bash复制opencv_version --verbose | grep -i cuda
原版VINS-Fusion在ARM平台表现不佳,GPU加速版需要特别注意以下几点:
首先修改CMakeLists.txt中的OpenCV路径:
cmake复制include(/usr/local/share/OpenCV/OpenCVConfig.cmake)
然后处理库文件冲突问题,在四个关键模块(camera_models、global_fusion、loop_fusion、vins_estimator)的CMakeLists中添加:
cmake复制list(REMOVE_ITEM catkin_LIBRARIES "/usr/lib/aarch64-linux-gnu/libopencv_core.so.4.2.0")
list(REMOVE_ITEM catkin_LIBRARIES "/usr/lib/aarch64-linux-gnu/libopencv_imgproc.so.4.2.0")
实测发现还需要调整Eigen的内存对齐设置,编辑/usr/include/eigen3/Eigen/src/Core/util/Macros.h,约第900行处修改为:
cpp复制#define EIGEN_MAX_ALIGN_BYTES 16
编译Fast-Drone-250时,这些参数调优让性能提升了40%:
修改local_sensing/CMakeLists.txt:
cmake复制set(ENABLE_CUDA true)
set(CUDA_NVCC_FLAGS
-gencode arch=compute_87,code=sm_87;
-O3 --use_fast_math)
在catkin_make时建议增加这些参数:
bash复制catkin_make -DCMAKE_BUILD_TYPE=Release -j$(nproc)
遇到的最棘手问题是ROS的cv_bridge兼容性问题,解决方法是用新编译的OpenCV替换默认链接:
bash复制sudo ln -sf /usr/local/lib/libopencv_core.so.3.4 /opt/ros/noetic/lib/libopencv_core.so
飞控连接方面,Orin-NX的串口设备名与x86平台不同,需要特别注意:
bash复制sudo chmod 777 /dev/ttyTHS0
roslaunch mavros px4.launch fcu_url:="/dev/ttyTHS0:921600"
提高IMU采样率的方法也独具特色,在飞控SD卡创建/etc/extras.txt写入:
code复制mavlink stream -d /dev/ttyS3 -s HIGHRES_IMU -r 200
VINS标定时,建议修改realsense.launch中的参数:
xml复制<param name="enable_sync" value="true"/>
<param name="depth_fps" value="30"/>
<param name="infra_fps" value="30"/>
最后分享几个实用的性能监控命令:
查看GPU利用率:
bash复制sudo tegrastats --interval 1000
实时查看VINS处理延迟:
bash复制rostopic hz /vins_estimator/odometry
内存带宽监控:
bash复制sudo apt-get install nvtop
nvtop
经过这些优化,在Orin-NX上ego-planner的规划周期能从原来的120ms降至70ms,图像处理帧率稳定在20FPS以上。记得在长期运行时给开发板加装散热风扇,持续高温会导致CPU降频。