相機和livox激光雷達外參標定:在gazebo中搭建仿真場景
點擊下方卡片,關(guān)注“新機器視覺”公眾號
重磅干貨,第一時間送達
本篇在gazebo中搭建可以模擬產(chǎn)生livox_camera_lidar_calibration功能包需要的數(shù)據(jù)的仿真場景.
場景搭建要求
下面總結(jié)下,針對livox_camera_lidar_calibration功能包仿真都需要哪些內(nèi)容:
livox 激光雷達,可以產(chǎn)生livox激光雷達這種的固態(tài)雷達的數(shù)據(jù)
相機,生成圖像
棋盤標定板
矩形標定板
激光雷達和相機可以一起改變角度和位置(世界坐標系下)
這個場景要求想起了之前搭建的一個無人機和云臺,那么在上面再裝一個livox avia 和 一個 carema就OK了
云臺裝在一個無人機上,剛好可以移動及改變 雷達和相機的姿態(tài).
場景搭建
創(chuàng)建一個云臺掛在無人機上
這個是之前搭建好的,不重點說了,直接上圖,就是下面這個樣子

其中無人機和云臺的尺寸比較小,和livox和camera的比例不太一致,不過仿真就不那么追求完美了,可以用就行.
云臺是這樣的:

灰色的是云臺的gimbal_base_link,用于與無人機的連接,連接方式是固定的,所以云臺的航向是完全鎖定機頭方向的
<joint name="${name}_joint" type="fixed"> <parent link="${parent}"/> <child link="gimbal_base_link"/> <origin xyz="0 0 -0.05" rpy="${M_PI} 0 ${M_PI/2} " /> <axis xyz="0 0 1" /> </joint>藍色的是link1,向下延伸桿.與gimbal_base_link為固定連接.
紅色的是云臺平臺的主體link2 , 與link1, 連接一個joint,用于俯仰的控制
<joint name="swivel_J1" type="revolute"> <parent link="link_1"/> <child link="link_2"/> <origin xyz="0 0 ${SizeGain*0.01}" rpy="0 0 0" /> <axis xyz="1 0 0" /> <limit lower="-1.745" upper="2.356" effort="10" velocity="1.0" /> <joint_properties damping="0" friction="0"/> </joint> <transmission name="tran2"> <type>transmission_interface/SimpleTransmission</type> <joint name="swivel_J1"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor2"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission>創(chuàng)建一個livox 和camera 掛在云臺上
上面說了尺寸問題,為了避免數(shù)據(jù)被遮擋,需要將雷達和相機往前放
雷達和相機放在 link2 上, 為了標定外參,設(shè)置兩者的位置不重合,當然實際也不可能重合. 先設(shè)置一個簡單的位置
雷達與x軸偏-0.1 相機與x軸偏0.1,所以兩者僅在y方向上偏0.2.之后在進行外參標定的時候再把各方向的偏差加上

<joint name="camera_J2" type="fixed"> <parent link="link_2"/> <child link="camera_mount"/> <origin xyz="0.1 ${SizeGain*0.01+0.29} 0" rpy="${M_PI} 0 ${M_PI/2}" /> <axis xyz="1 0 0" /> <limit lower="-2.094" upper="2.670" effort="10" velocity="1.0" /> <joint_properties damping="0.0" friction="0.0"/> </joint> <joint name="lidar_joint" type="fixed"> <parent link="link_2"/> <child link="livox_lidar_link"/> <origin xyz="-0.1 ${SizeGain*0.01+0.29} 0.002" rpy="${180*M_PI/180} ${0*M_PI/180} ${M_PI*0.5}" /> <axis xyz="1 0 0" /> </joint>相機與激光雷達視野匹配
我們知道激光雷達是沒有鏡頭的,所以激光雷達的視場角是多少就是多少,無法改變.(實際場景中)
那么想讓相機與激光雷達的視野匹配,只能選擇相機的鏡頭,讓水平視場角和垂直視場角兩者更為接近.
激光雷達仿真對應(yīng)的具體型號是livox avia ,該雷達的視野如下:
非重復(fù)式掃描 70.4° * 77.2°
在gazebo中也是這樣設(shè)置的
<xacro:property name="horizontal_fov" value="70.4"/> <xacro:property name="vertical_fov" value="77.2"/>所以在gazebo中設(shè)置相機的參數(shù)如下:(水平角是70.4,像素是4096*3000)
<gazebo reference="camera_mount"> <turnGravityOff>false</turnGravityOff> <sensor type="camera" name="camera_node"> <update_rate>5</update_rate> <camera name="head"> <horizontal_fov>"${70.4*M_PI/180}"</horizontal_fov> <image> <width>4096</width> <height>3000</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.007</stddev> </noise> </camera> <plugin name="gazebo_camera" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>10</updateRate> <cameraName>/camera</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>camera_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> </sensor> </gazebo>rviz中檢查成像效果
在云臺前,放一個墻

看激光雷達的點云和相機的圖像的墻的占幅比,如果上面調(diào)的視野一致的化,那么應(yīng)該不會差太多.

墻橫過來的效果

創(chuàng)建標定棋盤
編輯一個棋盤的sdf文件,這種文件太長了,就不在這放了. 展示下想讓棋盤待在空中不掉下來的關(guān)鍵部分:

static 為true 則不受重力影響
pose 就是 在world 的位置 x y z 和三個姿態(tài)角

在rviz中檢查下標定棋盤別太小就行.

創(chuàng)建標定板
標定板最好可以設(shè)置大點的,矩形板就行

<?xml version='1.0'?><sdf version="1.4"><model name="board"> <pose>4 0 2 0 1.57079 0</pose> <static>true</static> <link name="board"> <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> <inertial> <mass>0.01</mass> <inertia> <!-- interias are tricky to compute --> <!-- http://answers.gazebosim.org/question/4372/the-inertia-matrix-explained/ --> <ixx>0.083</ixx> <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) --> <ixy>0.0</ixy> <!-- for a box: ixy = 0 --> <ixz>0.0</ixz> <!-- for a box: ixz = 0 --> <iyy>0.083</iyy> <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) --> <iyz>0.0</iyz> <!-- for a box: iyz = 0 --> <izz>0.083</izz> <!-- for a box: izz = 0.083 * mass * (x*x + y*y) --> </inertia> </inertial> <collision name="collision"> <geometry> <box> <size>0.02 0.02 0.005</size> </box> </geometry> </collision> <visual name="sqr11"> <geometry> <box> <size>2 2.5 0.005</size> </box> </geometry> <material> <ambient>0 0 0 1</ambient> <diffuse>0 0 0 1</diffuse> <specular>0.1 0.1 0.1 1</specular> <emissive>0 0 0 0</emissive> </material> </visual> </model></sdf>場景效果檢測
最后控制無人機飛起來,然后看標定板在相機和雷達里的視野情況


本文僅做學(xué)術(shù)分享,如有侵權(quán),請聯(lián)系刪文。
