四轮车仿真平台搭建

一、仿真模型创建

1.1 link创建

link包含三大主要部分,分别是可视化的<visual> .. </visual>,碰撞属性<collision> ... </collision> 以及惯性参数<inertial> ... <inertial>
以小车的车身为例,

    <!-- 可视化 -->
    <visual>
        <origin xyz=" 0 0 0" rpy="0 0 0" />
        <geometry>
            <box size="0.40 0.20 0.16"/>
        </geometry>
        <material name="yellow" />
    </visual>

    <!-- 碰撞属性 -->
    <collision>
        <origin xyz=" 0 0 0" rpy="0 0 0" />
        <geometry>
            <box size="0.40 0.20 0.16"/>
        </geometry>
    </collision>  

    <!-- 惯性参数 -->
    <xacro:property name="m"   value="2" />
    <xacro:property name="r" value="0.06"/>
    <xacro:property name="h" value="0.025"/>
    <inertial>
        <mass value="m" />
        <inertia ixx="${2*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
            iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
            izz="${m*r*r/2}" /> 
    </inertial>

1.2 gazebo标签

gazebo工具用于小车的仿真,所以需要在link里面添加其标签。注意的是gazebo中的颜色要重新定义。

    <gazebo reference="base_link">
        <material>Gazebo/Blue</material>
    </gazebo>

1.3 传动装置

为模型的joint处添加传动转置,主要是车轮和车身的连接处。

    <transmission name="${prefix}_wheel_joint_trans">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${prefix}_wheel_joint" >
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        </joint>
        <actuator name="${prefix}_wheel_joint_motor">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

1.4 控制器插件

因为是四轮驱动,所以选择Skid Steering Drive的模式。

<gazebo>
    <plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
        <updateRate>100.0</updateRate>
        <robotNamespace>/</robotNamespace>
        <leftFrontJoint>front_left_wheel_joint</leftFrontJoint>
        <rightFrontJoint>front_right_wheel_joint</rightFrontJoint>
        <leftRearJoint>back_left_wheel_joint</leftRearJoint>
        <rightRearJoint>back_right_wheel_joint</rightRearJoint>
        <wheelSeparation>0.4</wheelSeparation>
        <wheelDiameter>0.215</wheelDiameter>
        <robotBaseFrame>base_link</robotBaseFrame>
        <torque>20</torque>
        <topicName>cmd_vel</topicName>
        <broadcastTF>false</broadcastTF>
    </plugin>
</gazebo>

1.5 模型测试

最后将模型加载进gazebo空间,测试。

Figure 1 仿真四轮车

二、传感器仿真

通过仿真传感器,我们可以降低实验成本,并且高效地测试不同环境下的算法性能。以搭载相机和激光雷达的四轮车为例。

2.1 相机

<!-- camera -->
<gazebo reference="camera_link">
    <sensor type="camera" name="camera1">
        <update_rate>30.0</update_rate>
        <camera name="head">
            <horizontal_fov>1.3962634</horizontal_fov>
            <image>
                <width>800</width>
                <height>800</height>
                <format>R8G8B8</format>
            </image>
            <clip>
                <near>0.02</near>
                <far>300</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.007</stddev>
            </noise>
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
            <alwaysOn>true</alwaysOn>
            <updateRate>0.0</updateRate>
            <cameraName>rrbot/camera1</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>

其中<sensor>... </sensor>是描述传感器的标签,内部包含类型type,参数,仿真插件等信息。以相机为例,传感器类型为camera, 在<camera> .. </camera>中描述了相机的分辨率,编码格式,图像范围,噪音参数等信息。在<plugin> ... </plugin>中加载了相机的仿真插件libgazebo_ros_camera.so,插件中设置了其命名空间,话题和参考坐标系。

2.2 激光雷达

<!-- laser -->
<gazebo reference="laser_link">
    <sensor type="ray" name="rplidar">
        <pose>0 0 0 0 0 0</pose>
        <visualize>false</visualize>
        <update_rate>5.5</update_rate>
        <ray>
            <scan>
                <horizontal>
                <samples>360</samples>
                <resolution>1</resolution>
                <min_angle>-3</min_angle>
                <max_angle>3</max_angle>
                </horizontal>
            </scan>
            <range>
                <min>0.10</min>
                <max>6.0</max>
                <resolution>0.01</resolution>
            </range>
            <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.0</mean>
                <stddev>0.01</stddev>
            </noise>
        </ray>
        <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
            <topicName>/scan</topicName>
            <frameName>laser_link</frameName>
        </plugin>
    </sensor>
</gazebo>

<sensor>... </sensor>的表示形式与相机类似。在激光雷达中<ray> ... </ray>中描述了其性能参数。在<plugin> ... </plugin>中加载的仿真插件为libgazebo_ros_laser.so。

2.3 其它传感器

Gazebo的传感器插件还有很多,比如Multicamera,Depth Camera,Openni Kinect,GPU Laser,Block Laser,F3D,Force,IMU等等,更详细的介绍可参考官网

2.4 模型测试

搭载传感器后,使用gazebo工具进行仿真测试。

Figure 2 仿真车搭载相机和激光雷达

最后可以在rviz观察传感器的模拟数据。

Figure 3 传感器数据显示

参考代码


   转载规则


《四轮车仿真平台搭建》 kieranych 采用 知识共享署名 4.0 国际许可协议 进行许可。
  目录