Github地址https://github.com/KL-Lee/Showimg.git
最近在做机器人项目,使用ROS+Gazebo仿真环境,首先在蛇型机器人的头部添加Kinect深度相机模型。打开模型的urdf文件。添加深度相机模块。代码如下所示:
<!--camera-->
<link name="camera_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<sphere radius="0.01" />
</geometry>
<material name="black">
<color rgba="0 0 0 0.95"/>
</material>
</visual>
</link>
<joint name="camera_joint" type="fixed">
<origin xyz="0.05 0 0.0015" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
<!--gazebo标签描述相机插件-->
<gazebo reference="camera_link"> <!--这一步说明插件作用的对象-->
<sensor type="depth" name="camera">
<update_rate>30.0</update_rate> <!--摄像头频率-->
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov> <!--摄像头可视范围-->
<image>
<width>640</width> <!--分辨率-->
<height>480</height>
<format>R8G8B8</format> <!--数据格式-->
</image>
<clip>
<near>0.02</near> <!--最近距离-->
<far>300</far> <!--最远距离-->
</clip>
</camera>
<!--加载相机插件-->
<