在gazebo中仿真四轮差速模型
首先,直接查看以下的xacro四轮机器人描述文件。
<?xml version="1.0"?>
<robot name="robot_walleva" xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="black">
<color rgba="0 0 0 1" />
</material>
<material name="yellow">
<color rgba="1 0.4 0 1" />
</material>
<material name="red">
<color rgba="1 0 0 1" />
</material>
<xacro:property name="wheel_mass" value="1"/>
<xacro:property name="wheel_radius" value="0.06"/>
<xacro:property name="wheel_length" value="0.08"/>
<xacro:property name="M_PI" value="3.1415926"/>
<xacro:property name="base_mass" value="5"/>
<xacro:property name="wheel_joint_x" value="0.22"/>
<xacro:property name="wheel_joint_y" value="0.20"/>
<xacro:property name="wheel_joint_z" value="0.00"/>
<xacro:property name="base_a" value="0.44"/>
<xacro:property name="base_b" value="0.36"/>
<xacro:property name="base_h" value="0.12"/>
<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(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>
</xacro:macro>
<xacro:macro name="box_inertial_matrix" params="m a b h">
<inertial>
<mass value="${m}" />
<!-- xacro has a terriable issue, it can't calculate h*h, but a*a -->
<inertia ixx="${m*(b*b+0.16*0.16)/12}" ixy="0" ixz="0"
iyy="${m*(0.16*0.16+a*a)/12}" iyz="0"
izz="${m*(a*a+b*b)/12}" />
</inertial>
</xacro:macro>
<xacro:macro name="wheel" params="prefix x_reflect y_reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="${x_reflect*wheel_joint_x} ${y_reflect*wheel_joint_y} ${-base_h/2}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
<material name="black" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
</link>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
<mu1>10000000</mu1>
<mu2>10000000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
<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>
</xacro:macro>
<xacro:macro name="robot_walleva_base_gazebo">
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<gazebo reference="base_footprint">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_h/2+wheel_radius}" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>
<link name="base_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<box size="${base_a} ${base_b} ${base_h}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<box size="${base_a} ${base_b} ${base_h}"/>
</geometry>
</collision>
<box_inertial_matrix m="${base_mass}" a="${base_a}" b="${base_b}" h="{base_h}" />
</link>
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
<wheel prefix="left_front" x_reflect="1" y_reflect="1" />
<wheel prefix="right_front" x_reflect="1" y_reflect="-1" />
<wheel prefix="left_back" x_reflect="-1" y_reflect="1" />
<wheel prefix="right_back" x_reflect="-1" y_reflect="-1" />
<!-- controller -->
<gazebo>
<plugin name="skid_steer_drive_controller"
filename="libgazebo_ros_skid_steer_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<updateRate>100.0</updateRate>
<leftFrontJoint>left_front_wheel_joint</leftFrontJoint>
<leftRearJoint>left_back_wheel_joint</leftRearJoint>
<rightFrontJoint>right_front_wheel_joint</rightFrontJoint>
<rightRearJoint>right_back_wheel_joint</rightRearJoint>
<wheelSeparation>${2*wheel_joint_y}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<torque>100</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
</xacro:macro>
<xacro:include filename="$(find robot_model_simu)/urdf/sensors/hokuyo_gazebo.xacro" />
<xacro:hokuyo_model prefix="hokuyo" />
<joint name="hokuyo_joint" type="fixed">
<origin xyz="0 0 ${base_h/2+0.025}" rpy="0 0 0" />
<parent link="base_link" />
<child link="hokuyo_link" />
</joint>
<xacro:include filename="$(find robot_model_simu)/urdf/sensors/camera_gazebo.xacro" />
<xacro:usb_camera prefix="camera" />
<joint name="camera_joint" type="fixed">
<origin xyz="${base_a/2} 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="camera_link" />
</joint>
<xacro:robot_walleva_base_gazebo />
</robot>
在gazebo中加载之后, 不难发现, 我们的机器人前后移动比较灵敏, 但是左右转向很不明显, 这是因为四轮在原地旋转的时候, 轮子会受到比较大的侧向阻力, 导致机器人的驱动力和地面摩擦系数不匹配,难以驱动,那么如何解决呢?
解决四轮差速在gazebo中转向不明显的问题
如下xacro描述文件:
添加轮子的摩擦系数以及刚性, 具有较大的摩擦系数,能更大程度地发挥轮子的驱动能力, 双轮差速模型除了前进的阻力,没有其他方向的阻力, 只要克服静摩擦力,便能够运动起来。
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
<mu1>10000000</mu1>
<mu2>10000000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
在gazebo运动控制插件中, 添加轮子的力矩, 加强轮子的驱动能力。
<gazebo>
<plugin name="skid_steer_drive_controller"
filename="libgazebo_ros_skid_steer_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<updateRate>100.0</updateRate>
<leftFrontJoint>left_front_wheel_joint</leftFrontJoint>
<leftRearJoint>left_back_wheel_joint</leftRearJoint>
<rightFrontJoint>right_front_wheel_joint</rightFrontJoint>
<rightRearJoint>right_back_wheel_joint</rightRearJoint>
<wheelSeparation>${2*wheel_joint_y}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<torque>100</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>