ros2-6.4.5 gazebo传感器仿真
6.4.5 激光雷达仿真
在文件夹src/fishbot_description/urdf/fishbot/plugins新建文件:
gazebo_sensor_plugin.xacro,代码如下:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="gazebo_sensor_plugin">
<gazebo reference="laser_link">
<sensor name="laserscan" type="ray">
<plugin name="laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<!-- 坐标系-->
<frame_name>laser_link</frame_name>
</plugin>
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>5</update_rate>
<pose>0 0 0 0 0 0</pose>
<!-- 激光传感器配置 -->
<ray>
<!-- 设置扫描范围 -->
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<!-- 设置扫描距离 -->
<range>
<min>0.120000</min>
<max>8.0</max>
<resolution>0.015000</resolution>
</range>
<!-- 设置噪声 -->
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
</sensor>
</gazebo>
</xacro:macro>
</robot>
激光雷达的作用是测距。
构建后,运行效果如下,中间圆圈是雷达盲区。
rviz中显示,点做了放大
激光雷达数据
bohu@bohu-TM1701:~/chapt6$ ros2 topic echo /scan --once
header:
stamp:
sec: 3161
nanosec: 666000000
frame_id: laser_link
angle_min: 0.0
angle_max: 6.28000020980835
angle_increment: 0.01749303564429283
time_increment: 0.0
scan_time: 0.0
range_min: 0.11999999731779099
range_max: 8.0
ranges:
- 2.933198928833008
- 2.9556350708007812
- 2.906764030456543
- 2.91933536529541
...
6.4.6 IMU 仿真
在上面的传感器补充下IMU的模块,IMU的作用
<gazebo reference="imu_link">
<sensor name="imu_sensor" type="imu">
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=imu</remapping>
</ros>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<update_rate>100</update_rate>
<always_on>true</always_on>
<!-- 六轴噪声设置 -->
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
<bias_mean>0.0000075</bias_mean>
<bias_stddev>0.0000008</bias_stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
<bias_mean>0.1</bias_mean>
<bias_stddev>0.001</bias_stddev>
</noise>
</z>
</linear_acceleration>
</imu>
</sensor>
</gazebo>
数据:
bohu@bohu-TM1701:~/chapt6$ ros2 topic echo /imu --once
header:
stamp:
sec: 3265
nanosec: 844000000
frame_id: base_footprint
orientation:
x: 3.4019740082303945e-07
y: 5.390785776959641e-10
z: -8.889597953958663e-05
w: 0.9999999960486946
orientation_covariance:
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
angular_velocity:
x: 0.0009924864783867119
y: 9.300519556695106e-05
z: -0.00038422782487058645
angular_velocity_covariance:
- 4.0e-08
- 0.0
- 0.0
- 0.0
- 4.0e-08
- 0.0
- 0.0
- 0.0
- 4.0e-08
linear_acceleration:
x: 0.08628854072137004
y: 0.11112931359461642
z: 9.902435504654651
linear_acceleration_covariance:
- 0.00028900000000000003
- 0.0
- 0.0
- 0.0
- 0.00028900000000000003
- 0.0
- 0.0
- 0.0
- 0.00028900000000000003
---
IMU的作用,IMU固定在机器人身上,当机器人姿态发生变化时,IMU数据会发生变化,当机器人原地打滑时,轮子转动里程计变化但是IMU数据不变,这样可以确认机器人发生打滑。
6.4.7 深度相机仿真
深度相机Z轴向前,所以首先需要调整相机旋转,增加虚拟部件camera_optical_joint 。
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:include filename="$(find fishbot_description)/urdf/fishbot/common_inertia.xacro" />
<xacro:macro name="camera_xacro" params="xyz">
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.02 0.10 0.02" />
</geometry>
<material name="green">
<color rgba="0.0 1.0 0 0.5" />
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.02 0.10 0.02" />
</geometry>
<material name="green">
<color rgba="0.0 1.0 0 0.5" />
</material>
</collision>
<xacro:box_inertia m="0.01" w="0.02" h="0.10" d="0.02" />
</link>
<link name="camera_optical_link"></link>
<joint name="camera_optical_joint" type="fixed">
<parent link="camera_link" />
<child link="camera_optical_link" />
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}" />
</joint>
<joint name="camera_joint" type="fixed">
<!-- 父部件 -->
<parent link="base_link" />
<!-- 子部件 -->
<child link="camera_link" />
<!-- 子部件相对父部件的平移和旋转 -->
<origin xyz="${xyz}" rpy="0 0 0" />
</joint>
</xacro:macro>
</robot>
在gazebo_sensor_plugin.xacro 增加深度相机仿真配置
<gazebo reference="camera_link">
<sensor type="depth" name="camera_sensor">
<plugin name="depth_camera" filename="libgazebo_ros_camera.so">
<frame_name>camera_optical_link</frame_name>
</plugin>
<always_on>true</always_on>
<update_rate>10</update_rate>
<camera name="camera">
<horizontal_fov>1.5009831567</horizontal_fov>
<image>
<width>800</width>
<height>600</height>
<format>R8G8B8</format>
</image>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
</sensor>
</gazebo>
重新构建后运行,在gazebo 查看
在rviz查看
在rqt 查看图片