环境:ubuntu16.04 ros-kinetic gazebo7.16
来源:激光传感器\超声波传感器\深度相机\普通相机\碰撞传感器的仿真插件使用,以及定义样式理解不清楚的话,编写有仿真需要的urdf的话,比较麻烦.所以,就总结一下轮式机器人所用的仿真传感器在urdf里面定义方式.
这些传感器就是采用链接里面案例,加上下面代码进行展示:
https://blog.csdn.net/qq_45701501/article/details/107521623
激光传感器/超声波传感器/深度相机/普通相机/碰撞传感器仿真编写样式:
<!--laser_sensor-->
<joint name="laser_sensor_joint" type="fixed">
<origin xyz="0 0 0.3"/>
<parent link="base_link"/>
<child link="laser"/>
</joint>
<link name="laser">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.02"/>
</geometry>
</visual>
<collision >
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.02"/>
</geometry>
</collision>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<gazebo reference="laser">//对应link的名称
<sensor type="ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>//表示雷达数据线在gazebo里面可见
<update_rate>30</update_rate>//雷达数据更新频率
<ray>
<!--define the line parameter of laser_sensor-->
<scan>
<horizontal>//垂直方向
<samples>720</samples>//线条数
<resolution>1</resolution>//分辨率
<min_angle>-1.57</min_angle>//最小弧度
<max_angle>1.57</max_angle>//最大弧度
</horizontal>
</scan>
<range>
<min>0.08</min>//最近数据获取点
<max>3</max>//最远数据获取点
<resolution>0.02</resolution>
</range>
<!--define noise-->
<noise>//噪声设置
<type>gaussian</type>//噪声类型
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0</mean>
<stddev>0.04</stddev>
</noise>
</ray>
<!--define the topic of the senser laser1 between the gazebo and ros in simulation information exchange.-->
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_laser.so">//插件类型为laser
<topicName>laser</topicName>//雷达数据的topic名称
<frameName>laser</frameName>//发数据依附的link
</plugin>
</sensor>
</gazebo>
<!--ultrasonic_sensor-->
<joint name="ultrasonic_sensor_joint" type="fixed">
<axis xyz="0 0 0" />
<origin xyz="-0.04 0 0.3" rpy="0 0 3.14"/>
<parent link="base_link"/>
<child link="ultrasonic_sensor"/>
</joint>
<link name="ultrasonic_sensor">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</visual>
<collision >
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</collision>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<!--the senser laser in gazebo,be careful that the names of reference and link should be same-->
<gazebo reference="ultrasonic_sensor">
<sensor type="ray" name="ultrasonic_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<!--define the line parameter of laser senser -->
<scan>
<horizontal>
<samples>8</samples>
<resolution>1</resolution>
<min_angle>-0.14</min_angle>
<max_angle>0.14</max_angle>
</horizontal>
<vertical>//水平方向参数设置
<samples>8</samples>
<resolution>1</resolution>
<min_angle>-0.14</min_angle>
<max_angle>0.14</max_angle>
</vertical>
</scan>
<range>
<min>0.05</min>
<max>1</max>
<resolution>0.1</resolution>
</range>
</ray>
<!--define the topic of the senser laser between the gazebo and ros in simulation information exchange.-->
<plugin name="ultrasonic_sensor_controller" filename="libgazebo_ros_range.so">//超声波采用的插件为range类型,注意与激光雷达的区分
<gaussianNoise>0.01</gaussianNoise>
<alwaysOn>true</alwaysOn>
<fov>0.1</fov>
<topicName>ultrasonic_sensor</topicName>
<frameName>ultrasonic_sensor</frameName>
<radiation>ultrasound</radiation>//表示类型为超声波
</plugin>
</sensor>
</gazebo>
<!--depth_camera-->
<joint name="Depthcamera_left_to_base_link" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="-0.1 0.1 0.3" rpy="0 0 1.57"/>
<parent link="base_link"/>
<child link="depth_camera"/>
</joint>
<link name="depth_camera">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.1 0.01"/>
</geometry>
<material name="red"/>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="depth_camera_adjust" type="fixed">
<origin xyz="0 0 0" rpy="-1.570795 0 -1.570795 "/>
<parent link="depth_camera"/>
<child link="depth_camera_adjust"/>
</joint>
<link name="depth_camera_adjust"></link>
<gazebo reference="depth_camera">
<sensor name="depth_camera" type="depth">
<update_rate>36</update_rate>
<camera>
<horizontal_fov>1.4</horizontal_fov>//水平视角设置
<image>//图片设置
<width>720</width>
<height>520</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>3</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.008</stddev>
</noise>
</camera>
<plugin name="depth_camera_controller" filename="libgazebo_ros_openni_kinect.so">//深度相机仿真插件
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0</updateRate>
<cameraName>depth_camera</cameraName>
<imageTopicName>/depth_camera/color/image_raw</imageTopicName>//以下都是该深度相机一些topic
<cameraInfoTopicName>/depth_camera/color/camera_info</cameraInfoTopicName>
<depthImageTopicName>/depth_camera/depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>/depth_camera/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/depth_camera/depth/points</pointCloudTopicName>
<frameName>depth_camera_adjust</frameName>//这是因为深度相机的发射的点云数据的link,在gazebo和ros里面有区别的,所以需要添加一个附加link.普通相机也一样
<pointCloudCutoff>0.3</pointCloudCutoff>
<pointCloudCutoffMax>4.0</pointCloudCutoffMax>
<distortionK1>0.00000003</distortionK1>
<distortionK2>0.00000003</distortionK2>
<distortionK3>0.00000003</distortionK3>
<distortionT1>0.00000003</distortionT1>
<distortionT2>0.00000003</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
<!--general_camera-->
<joint name="general_camera_to_base_link" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="-0.1 -0.1 0.3"
rpy="0 0 -1.57"/>
<parent link="base_link"/>
<child link="general_camera"/>
</joint>
<link name="general_camera">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.1 0.01"/>
</geometry>
<material name="red"/>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="general_camera_adjust" type="fixed">
<origin xyz="0 0 0" rpy="0 1.57 0"/>
<parent link="general_camera"/>
<child link="general_camera_adjust"/>
</joint>
<link name="general_camera_adjust"></link>
<gazebo reference="general_camera">
<sensor type="camera" name="general_camera">
<update_rate>36.0</update_rate>
<camera name="general_camera">
<horizontal_fov>1.3</horizontal_fov>
<image>
<width>720</width>
<height>520</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.07</near>
<far>420</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.009</stddev>
</noise>
</camera>
<plugin name="general_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>36.0</updateRate>
<cameraName>general_camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>general_camera_adjust</frameName>//发射topic依附的是附加link
<hackBaseline>0.1</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<!--crash_sensor-->
<joint name="crash_sensor_joint" type="fixed">
<origin xyz="-0.3 0 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="crash_sensor"/>
</joint>
<link name="crash_sensor">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.5 0.1"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.01 0.5 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1000" ixy="0" ixz="0" iyy="1000" iyz="0" izz="1000"/>
</inertial>
</link>
<gazebo reference="crash_sensor">
<sensor type="contact" name="crash_sensor">
<always_on>true</always_on>
<update_rate>100.0</update_rate>
<visualize>true</visualize>
<contact>
<collision>base_link_fixed_joint_lump__crash_sensor_collision_2</collision>//这个名称需要采用xacro->urdf->sdf格式转换,然后查看sdf,根据link名称来获取填写进来.
</contact>
<plugin name="crash_sensor_controller" filename="libgazebo_ros_bumper.so">//碰撞传感器的仿真插件
<updateRate>100</updateRate>
<bumperTopicName>crash_sensor</bumperTopicName>
<frameName>crash_sensor</frameName>
</plugin>
</sensor>
</gazebo>
使用rostopic list验证新增topic有:
激光雷达:/laser
超声波:/ultrasonic_sensor
碰撞传感器:/crash_sensor
普通相机:/general_camera/....
深度相机:/depth_camera/...
.
加载到gazebo基本效果(上侧扇形蓝色为激光雷达,下侧层状蓝色为超声波)如图:
碰撞传感器的验证:
rostopic echo /crash_sensor
然后让超声波下方的碰撞传感器(灰色横条)碰地,基本输出样式如:
header:
seq: 2031
stamp:
secs: 26
nsecs: 855000000
frame_id: "crash_sensor"
states:
-
info: "Debug: i:(0/5) my geom:robot::base_link::base_link_fixed_joint_lump__crash_sensor_collision_2\
\ other geom:ground_plane::link::collision time:26.846000000\n"
collision1_name: "robot::base_link::base_link_fixed_joint_lump__crash_sensor_collision_2"
collision2_name: "ground_plane::link::collision"
wrenches:
-
force:
x: 79.4242589182
y: -0.228486394725
z: 254.149542944
torque:
x: 63.5259609594
y: 72.0490770425
z: -19.7877205646
-
force:
x: -1.41168461752e-86
y: -1.8088522156e-86
z: 2.16294644862e-86
torque:
x: -6.3118284064e-87
y: 7.17561107117e-87
z: 1.88137293794e-87
total_wrench:
force:
x: 79.4242589182
y: -0.228486394725
z: 254.149542944
torque:
x: 63.5259609594
y: 72.0490770425
z: -19.7877205646
contact_positions:
-
x: -0.29879588399
y: 0.250076586998
z: -3.30430484684e-06
-
x: -0.295594736747
y: -0.249913165553
z: -2.87280618165e-06
至此,基本上,轮式运输机器人仿真所需要的建图,导航,避障相关的一般雷达\相机\接触传感器的定义方式都齐全了.
补充一个知识点,使用libgazebo_ros_range.so
时候,需要定义radiation
的类型,目前个人知道的可以是infrared
(红外形),ultrasound
(超声波)类型.
#####################
好记性不如烂笔头
'–20200817