簡介:介紹銀牛微電子 3D 機器視覺R132相機 在EHub_tx1_tx2_E100載闆,TX1核心子產品環境(Ubuntu18.04)下測試ROS驅動,打開攝像頭圖像和檢視深度圖和點雲圖,本文的前提條件是你的TX1裡已經安裝了ROS版本:Melodic。關于測試硬體EHub_tx1_tx2_E100載闆請檢視:EdgeBox_EHub_tx1_tx2_E100 開發闆評測_機器人虎哥的部落格-CSDN部落格
大家好,我是虎哥,最近都在看如何更好的實作機器人的避障,補死角的方案,查閱了好幾款深度相機的方案,正好手裡還有之前采購的銀牛 的R132模組,有感于網上對于上手就可以簡單玩起來的說明比較少,是以總結一下自己的簡單測試經驗,分享給大家。
![](https://img.laitimes.com/img/9ZDMuAjOiMmIsIjOiQnIsIyZuBnLyIDN1czMwITMlFzYiVGZhBjY3QTY1MWZlJTM2QTMkBzLc52YucWbp5GZzNmLn9Gbi1yZtl2Lc9CX6MHc0RHaiojIsJye.png)
官網入口是:模組-銀牛微電子(無錫)有限責任公司 官網資料有限。
目錄
一、 銀牛 “R132“ 深度相機
1.1 關鍵參數:
二、WIN 下測試流程
2.1 驅動安裝:
1、安裝驅動 步驟
2.2 SDK及 Inuview工具 安裝
2.3 Inuview工具 測試相機
1、活動流選擇顯示深度資料:
2、活動流選擇顯示RGB資料:
3、活動流選擇顯示IMU資料:
三、ROS 下測試流程
4.1 拷貝代碼
4.2 插入模組USB至闆子
4.3 安裝官方程式
4.4 測試啟動
4.5 RVIZ 顯示IMU資料
4.6 rqt_image_view RGB、紅外、深度圖
4.7 RVIZ RGB、紅外、深度圖
四. 隻啟動相機驅動的LAUNCH修改
修改
一、 銀牛 “R132“ 深度相機
主要配置
■ 基于IR主動有源立體深度傳感器
■ 0.2-4米深度測量範圍
■ 寬視場角(88°x 58°FoV)
■ RGB 攝像頭傳感器,與深度傳感器對齊
■ 采用Inuitive的NU4000多核計算機視覺與三維圖像處理器
■ 經過詳盡的内外參标定的機載慣性測量單元(IMU)
■ 功率低、體積小
■ 高速USB-Type C主機接口(USB 3.0)
■ 高速MIPI CSI 2.0主機接口
■ 支援Windows、Linux和Android OSs 作業系統
■ 可在所有照明條件下工作(從夜晚到白晝)
■ 應用程式接口,使應用層的設計變得更容易
1.1 關鍵參數:
詳細手冊擷取網站入口:客戶支援-銀牛微電子(無錫)有限責任公司
二、WIN 下測試流程
需要資料和對應軟體,需要聯系廠家直接要就可以。首先在WIN端測試,需要安裝驅動程式。R132是一種即插即用的USB裝置,包含一個專用的驅動程式。
2.1 驅動安裝:
沒安裝驅動程式前,将R132的USB口接入測試電腦:
1、安裝驅動 步驟
輕按兩下InuDriver_3.0.7.0-1.09_Setup_X64進行驅動安裝。
一路預設next即可。
安裝完畢後,即可以再自己電腦裝置管理器看到裝置了。
2.2 SDK及 Inuview工具 安裝
可以參考文檔:騰訊文檔
輕按兩下InuDev_Pro_4.16.0006.30_X64進行工具安裝
然後一路NEXT就可以。
支援工具軟體安裝完畢。
2.3 Inuview工具 測試相機
打開InuView工具
驗證位于視窗右上角的USB連接配接器圖示是否為藍色。
- 藍色USB圖示:模組已連接配接并正在運作
- 灰色USB圖示:模組未連接配接或未激活
預設顯示紅外資料,我們通過活動視窗流選擇可以顯示不同通道的資料:
1、活動流選擇顯示深度資料:
2、活動流選擇顯示RGB資料:
3、活動流選擇顯示IMU資料:
三、ROS 下測試流程
4.1 拷貝代碼
#解壓包
unzip Linux-arm64-Ubuntu18.04-ros.zip
官方目錄中有安裝步驟,要先執行了:
#插入模組:
1,sudo dpkg -i inudev-simplified_4.16.0006.30_arm64.deb
2,sudo dpkg -i ros-melodic-inudev-ros-nodelet_1.0.18-0bionic_arm64.deb
3,export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/Inuitive/InuDev/lib
4,roslaunch /opt/ros/melodic/share/inudev_ros_nodelet/launch/inudev_ros_nodelet.launch
4.2 插入模組USB至闆子
4.3 安裝官方程式
cd ~/Inuchip_ws/Linux-arm64-Ubuntu18.04-ros
sudo dpkg -i inudev-simplified_4.16.0006.30_arm64.deb
sudo dpkg -i ros-melodic-inudev-ros-nodelet_1.0.18-0bionic_arm64.deb
4.4 測試啟動
需要顯示器界面支援,我使用nomachine 連結我的闆子的。
#設定庫應用路徑
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/Inuitive/InuDev/lib
#啟動傳感器測試驅動
roslaunch /opt/ros/melodic/share/inudev_ros_nodelet/launch/inudev_ros_nodelet.launch
啟動之後,會彈出3個視窗,這個應該是官方為了友善測試所留的。可以全部3個視窗都關掉,不影響後續測試。
這個頁面,官方預留的可以用來可視化調整一些參數看。可以全部3個視窗都關掉,不影響後續測試。
關掉不影響後續測試。
新開一個終端:
rosnode list
/inudev_ros_nodelet
/link_broadcaster
/nodelet_manager
/rosout
/rqt_console
/rqt_reconfigure
rostopic list
/camera/aligned_depth_to_color/image_raw
/camera/aligned_depth_to_color/image_raw/compressed
/camera/aligned_depth_to_color/image_raw/compressed/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressed/parameter_updates
/camera/aligned_depth_to_color/image_raw/compressedDepth
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_updates
/camera/aligned_depth_to_color/image_raw/theora
/camera/aligned_depth_to_color/image_raw/theora/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/theora/parameter_updates
/camera/color/camera_info
/camera/color/image_raw
/camera/color/image_raw/compressed
/camera/color/image_raw/compressed/parameter_descriptions
/camera/color/image_raw/compressed/parameter_updates
/camera/color/image_raw/compressedDepth
/camera/color/image_raw/compressedDepth/parameter_descriptions
/camera/color/image_raw/compressedDepth/parameter_updates
/camera/color/image_raw/theora
/camera/color/image_raw/theora/parameter_descriptions
/camera/color/image_raw/theora/parameter_updates
/depth/depth2pc
/disparity/sensor_msgs/Image/Video/disparity
/features/camera/fisheye/features
/imu/sensor_msgs/Imu
/inudev_ros_nodelet/parameter_descriptions
/inudev_ros_nodelet/parameter_updates
/nav_msgs/sensor_msgs/Path
/nodelet_manager/bond
/pointcloud/sensor/PointCloud2
/rosout
/rosout_agg
/sensor_msgs/Image/Fisheye
/sensor_msgs/Image/Fisheye/compressed
/sensor_msgs/Image/Fisheye/compressed/parameter_descriptions
/sensor_msgs/Image/Fisheye/compressed/parameter_updates
/sensor_msgs/Image/Fisheye/compressedDepth
/sensor_msgs/Image/Fisheye/compressedDepth/parameter_descriptions
/sensor_msgs/Image/Fisheye/compressedDepth/parameter_updates
/sensor_msgs/Image/Fisheye/theora
/sensor_msgs/Image/Fisheye/theora/parameter_descriptions
/sensor_msgs/Image/Fisheye/theora/parameter_updates
/sensor_msgs/Image/Video/left/camera_info
/sensor_msgs/Image/Video/left/image
/sensor_msgs/Image/Video/right/camera_info
/sensor_msgs/Image/Video/right/image
/sensor_msgs/Image/camera_info
/tf
/vision_msgs/vision_msgs/Detections
4.5 RVIZ 顯示IMU資料
# 如果剛才沒有關相機節點,下面可以跳過,如果已經關閉,記得開一個終端,打開相機節點
#設定庫應用路徑
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/Inuitive/InuDev/lib
#啟動傳感器測試驅動
roslaunch /opt/ros/melodic/share/inudev_ros_nodelet/launch/inudev_ros_nodelet.launch
在一個新的終端,可以看到IMU話題和資料
# 新開一個節點,打開RVIZ
rosrun rviz rviz
Rviz中點選左下角Add添加rviz_imu_plugin,可以看見有坐标系出現,如果沒有需要安裝 (sudo apt-get install ros-melodic-imu-tools 安裝imu功能包)
這個時候你再動相機,圓錐箭頭就開始動了。
可以保留這個RVIZ配置:
4.6 rqt_image_view RGB、紅外、深度圖
上面已經打開了測試節點,此處行開一個終端,啟動rqt_image_view
rosrun rqt_image_view rqt_image_view
RGB圖:
紅外圖:
一看深度資訊圖,就會報錯:
暫時沒有搞清楚怎麼回事。
4.7 RVIZ RGB、紅外、深度圖
# 如果剛才沒有關相機節點,下面可以跳過,如果已經關閉,記得開一個終端,打開相機節點
#設定庫應用路徑
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/opt/Inuitive/InuDev/lib
#啟動傳感器測試驅動
roslaunch /opt/ros/melodic/share/inudev_ros_nodelet/launch/inudev_ros_nodelet.launch
# 新開一個節點,打開RVIZ
rosrun rviz rviz
測試過程中記錄了一下CPU的占用情況
四. 隻啟動相機驅動的LAUNCH修改
每次啟動官方的腳本檔案,都需要進行關閉那些視窗的操作,實際我們使用,應該也很少開啟那些視窗,我們可以選擇自己寫一個腳本本間來實作。
#啟動傳感器測試驅動
roslaunch /opt/ros/melodic/share/inudev_ros_nodelet/launch/inudev_ros_nodelet.launch
launch/inudev_ros_nodelet.launch 檔案的原始内容:
<launch>
<arg name="Service_ID" default="" />
<arg name="tf_prefix" default="" />
<arg name="stereo_namespace" default="stereo" />
<arg name="xyz_namespace" default="cloudify" />
<arg name="manager" default="nodelet_manager" />
<!-- "screen" or "log" -->
<arg name="output" default="log" />
<arg name="verbose" default="true" />
<arg name="run_stereo_image_proc" default="0" />
<arg name="run_disparity_to_depth" default="0" />
<!-- controls display of InuSW vide/disparity output -->
<arg name="run_image_view_video" default="0" />
<!-- controls display of ROS video->disparity processing display -->
<arg name="run_image_view_disparity" default="0" />
<arg name="run_image_view_depth" default="0" />
<arg name="run_image_view_fisheye" default="0" />
<arg name="run_image_view_RGB" default="0" />
<arg name="run_rqt_image_view" default="0" />
<arg name="run_rviz" default="0" />
<arg name="run_depth2xyz" default="0" />
<arg name="run_configure" default="1" />
<!-- controls loading disparity processing as nodelet (this now works) -->
<arg name="disparity_nodelet" default="0" />
<!-- controls disabling loading of unused image transports. -->
<arg name="disable_unused_transports" default="1" />
<!-- =================================== NO CONFIGURATION OPTIOS BELOW THIS POINT =================================== -->
<rosparam file="$(find inudev_ros_nodelet)/cfg/InuRosParams$(arg Service_ID).yaml" />
<!-- Topic remapping according to service ID -->
<remap from="/camera/aligned_depth_to_color/image_raw" to="/camera/aligned_depth_to_color/image_raw$(arg Service_ID)" />
<remap from="/camera/color/image_raw" to="/camera/color/image_raw$(arg Service_ID)" />
<remap from="/sensor_msgs/Image/Video/right/image" to="/sensor_msgs/Image/Video/right/image$(arg Service_ID)" />
<remap from="/sensor_msgs/Image/Video/left/image" to="/sensor_msgs/Image/Video/left/image$(arg Service_ID)" />
<remap from="/sensor_msgs/Image/Video/disparity" to="/sensor_msgs/Image/Video/disparity2$(arg Service_ID)" />
<remap from="/sensor/PointCloud" to="/sensor/PointCloud$(arg Service_ID)" />
<remap from="/sensor_msgs/Image/Fisheye" to="/sensor_msgs/Image/Fisheye$(arg Service_ID)" />
<remap from="/sensor_msgs/Path" to="/sensor_msgs/Path$(arg Service_ID)" />
<remap from="/sensor_msgs/Imu" to="/sensor_msgs/Imu$(arg Service_ID)" />
<remap from="/vision_msgs/Detections" to="/vision_msgs/Detections$(arg Service_ID)" />
<remap from="/camera/fisheye/features" to="/camera/fisheye/features$(arg Service_ID)" />
<group if="$(arg disable_unused_transports)" >
<include file="$(find inudev_ros_nodelet)/launch/inudev_ros_nodelet_transport_disable.launch" ns="sensor_msgs/Image/Depth" />
<include file="$(find inudev_ros_nodelet)/launch/inudev_ros_nodelet_transport_disable.launch" ns="sensor_msgs/Image/Webcam" />
<include file="$(find inudev_ros_nodelet)/launch/inudev_ros_nodelet_all_transports_disable.launch" >
<arg name="side" value="left" />
</include>
<include file="$(find inudev_ros_nodelet)/launch/inudev_ros_nodelet_all_transports_disable.launch" >
<arg name="side" value="right" />
</include>
</group>
<!-- create a console if output is *not* screen -->
<node if="$(eval arg('output')!='screen')" pkg="rqt_console" type="rqt_console" name="rqt_console" />
<!-- nodelet manager -->
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="$(arg output)" />
<!-- this is Inuitive's ROS nodelet -->
<node pkg="nodelet" type="nodelet" name="inudev_ros_nodelet$(arg Service_ID)" args="load inudev_ros_nodelet/CInuDevRosNodelet $(arg manager) TEST" output="$(arg output)" required="true">
<param name="verbose" value="false" />
<param name="log_pointcloud" value="false" />
</node>
<!-- view ROS info -->
<node pkg="rqt_gui" type="rqt_gui" name="rqt_gui" />
<!-- Static Transform Publisher -->
<node pkg="tf" type="static_transform_publisher" name="link_broadcaster$(arg Service_ID)" args="0.0 0.0 0.0 0 0 0 /map /camera_link$(arg Service_ID) 100" />
<node if="$(arg run_rqt_image_view)" pkg="rqt_image_view" type="rqt_image_view" name="rqt_image_view" output="$(arg output)" />
<!-- display InuSW disparity output -->
<node if="$(arg run_image_view_video)" pkg="image_view" type="stereo_view" name="image_view" args="_approximate_sync:=True" output="$(arg output)">
<param name="~window_name" value="Video" />
<remap from="stereo" to="/sensor_msgs/Image/Video" />
<param name="queue_size" value="5" />
</node>
<!-- Display of ROS video->disparity processing output -->
<node if="$(arg run_image_view_disparity)" pkg="image_view" type="stereo_view" name="disparity_view" output="$(arg output)">
<param name="~window_name" value="Disparity" />
<remap from="stereo" to="$(arg stereo_namespace)" />
<remap from="image" to="image_color" />
</node>
<node if="$(arg run_image_view_depth)" pkg="image_view" type="image_view" name="depth_view" respawn="true" respawn_delay="30" output="$(arg output)">
<param name="~window_name" value="Depth" />
<remap from="image" to="/sensor_msgs/Image/Depth" />
</node>
<node if="$(arg run_image_view_fisheye)" pkg="image_view" type="image_view" name="fisheye_view" respawn="true" respawn_delay="30" output="$(arg output)">
<param name="~window_name" value="Fisheye" />
<remap from="image" to="/sensor_msgs/Image/Fisheye" />
</node>
<node if="$(arg run_image_view_RGB)" pkg="image_view" type="image_view" name="RGB_view" respawn="true" respawn_delay="30" output="$(arg output)">
<param name="~window_name" value="RGB" />
<remap from="image" to="/camera/color/image_raw" />
</node>
<node if="$(arg run_depth2xyz)" pkg="nodelet" type="nodelet" name="cloudify" args="load depth_image_proc/point_cloud_xyz $(arg manager)" output="$(arg output)">
<remap from="sensor_msgs/Image" to="/sensor_msgs/Image/Depth" />
<remap from="sensor_msgs/CameraInfo" to="/sensor_msgs/Image/camera_info" />
</node>
<node if="$(arg run_rviz)" pkg="rviz" type="rviz" name="rviz" />
<group if="$(arg run_stereo_image_proc)" >
<!--
video to disparity processing
We repawn, as stereo_image_proc will exit if the topics it expects are not being published. Note it will
also not publish on its own, anless it's topics are subscribed to.
-->
<remap from="/$(arg stereo_namespace)/left/image_raw" to="/sensor_msgs/Image/Video/left/image" />
<remap from="/$(arg stereo_namespace)/right/image_raw" to="/sensor_msgs/Image/Video/right/image" />
<remap from="/$(arg stereo_namespace)/left/camera_info" to="/sensor_msgs/Image/Video/left/camera_info" />
<remap from="/$(arg stereo_namespace)/right/camera_info" to="/sensor_msgs/Image/Video/right/camera_info" />
<!--
stereo image processing
-->
<node unless="$(arg disparity_nodelet)" pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc" output="$(arg output)" ns="$(arg stereo_namespace)" respawn="true" respawn_delay="30" />
<node if="$(arg disparity_nodelet)" pkg="nodelet" type="nodelet" name="stereo_image_proc" output="$(arg output)" ns="$(arg stereo_namespace)" respawn="true" respawn_delay="30" args="load stereo_image_proc/disparity $(arg manager) --bond" />
</group>
<node if="$(arg run_configure)" pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" />
</launch>
修改
修改後,啟動試試:
糾錯,疑問,交流: [email protected]