目录
- 写在前面的话(重要!!!)
- gazebo中的参数设置
- 设置启动小车的初始姿态
- 发现车子与地面的接触点有问题(关键!!!)
- 查看接触点的步骤:
- 原始车轮设置
- 原始转向器设置
- 统一车轮和转向器的设置
- 最终结果
- 控制指令
- gif 动图显示
写在前面的话(重要!!!)
启动gazebo的时候,不给车子发送控制指令,总是无法禁止,会沿着一个方向转弯,我进行多种的尝试:
- 一开始以为是摩擦力的问题,给车轮设置了很大的摩擦力(十个0的那种),但是还是无法禁止。
- 车子质量的问题,把质量调小,车子还是会转弯,但是速度变慢了很多;把质量调大,车子转弯速度会加快很多。
- 车轮刚性的问题,这个没用,但是我发现了,这个设置小,车子碰撞地面和墙壁的话很容易弹飞,设置大的话,车子就不怎么受弹力的影响。
- 车轮阻尼的问题,这个有用,设置大了,车子真的会禁止不动,但是同时车轮转不动了,有点类似大力刹车,车轮卡死的感觉。
- 车轮惯性的问题,统一了惯量矩阵设置,但还是没用。
- 转向器和车轮的位置的问题,统一了转向器和车轮的位置,车轮惯性统一也要保持,这次才实现静止(成功!!!)。
gazebo中的参数设置
- mul1:摩擦力
- mul2:摩擦力
- kp: 刚性大小,表示车子对抗形变的能力,越大,表示车子对抗形变的能力越强,小的话车子会像篮球一样反复弹跳。
- kd: 阻尼大小,表示车子的制动能力,越大,表示刹车的力度越大,越不会滑动。
- min_depth:这个标签设置了碰撞体之间的最小接触深度为0.001。这意味着在模拟碰撞时,如果两个碰撞体的接触深度小于0.001,系统将视它们为没有接触。
- maxVel:定义了最大线速度为20。
- fdir1:指定了摩擦力的方向。
设置启动小车的初始姿态
spawn_x_val = '0.0'
spawn_y_val = '0.0'
spawn_z_val = '0.756'#0.755879
spawn_yaw_val = '0.0'
这些值设置的是车子在gazebo中出现的位置,在gazebo中,Z轴默认垂直地面向上(蓝色),X轴(红色),Y轴(绿色)。gazebo是一个支持仿真物理空间的软件。
假设单位是米,如果你设置了初始Z轴的值是10米【spawn_z=10.0】,然后你的车子中心点(base_link)离车轮触地的高度是1米,那么车子就会从10米高空出现,然后因为重力的影响下落砸到地面上。
如果你设置初始Z轴的值是0米,由于你的车子的中心点的高度是1米,那么你的车子初始位置就是被压入地面1米以下,那么因为地面的弹力作用,会导致车子弹射进入高空再下落。
这里因为我的车子的中心点设置比车胎底部高出0.7558米,所以我需要考虑这个高度,防止车子被压入地面。(在下图中车子的pose栏的z值偏小,因为车轮因为重力影响被挤压,高度有细微变化)
# Pose where we want to spawn the robot
spawn_x_val = '0.0'
spawn_y_val = '0.0'
spawn_z_val = '0.756'#0.755879
spawn_yaw_val = '0.0'
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
arguments=['-topic', 'robot_description',
'-entity', f'{robot_name_in_model}',
'-x', spawn_x_val,
'-y', spawn_y_val,
'-z', spawn_z_val,
'-Y', spawn_yaw_val
],
output='screen')
发现车子与地面的接触点有问题(关键!!!)
在 gazebo 中发现, 四个轮子中有个轮子(右后轮)与地面没有接触点(不施加力下,车子无法静止的关键原因),检查 xacro 发现车子车轮和转向器的原点的坐标没有统一,惯性也没统一,这是可能是由于solidworks导出urdf出现的误差,也有可能本身solidworks设计的车子就没有考虑这些。
后续我通过xacro函数对 车轮(wheel)和转向器(orient)进行了统一设置,车子实现了静态禁止。
查看接触点的步骤:
gazebo 左上角窗口 World, 在 Models中,右键选择 car_urdf_gazebo,View 设置为 transparent(透明),然后在菜单栏 View 勾选 Contacts 即可
原始车轮设置
原始转向器设置
统一车轮和转向器的设置
<xacro:macro name='orient_joint' params='prefix:=left_front'>
<joint name="${prefix}_orient_joint"
type="continuous">
<xacro:if value="${prefix == 'left_front'}">
<origin
xyz="0.22654 0.5868 -0.068"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'left_back'}">
<origin
xyz="-0.77346 0.5868 -0.068"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'right_front'}">
<origin
xyz="0.22654 -0.5868 -0.068"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'right_back'}">
<origin
xyz="-0.77346 -0.5868 -0.068"
rpy="0 0 0" />
</xacro:if>
<parent
link="base_link" />
<child
link="${prefix}_orient_Link" />
<axis
xyz="0 0 -1" />
</joint>
</xacro:macro>
<xacro:macro name='wheel_joint' params='prefix:=left_front'>
<joint name="${prefix}_wheel_joint"
type="continuous">
<xacro:if value="${prefix == 'left_front'}">
<origin
xyz="0 0.04825 -0.385"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'left_back'}">
<origin
xyz="0.001828 0.04825 -0.385"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'right_front'}">
<origin
xyz="0 -0.04825 -0.385"
rpy="0 0 0" />
</xacro:if>
<xacro:if value="${prefix == 'right_back'}">
<origin
xyz="0.001828 -0.04825 -0.385"
rpy="0 0 0" />
</xacro:if>
<parent
link="${prefix}_orient_Link" />
<child
link="${prefix}_wheel_Link" />
<axis
xyz="0 1 0" />
</joint>
</xacro:macro>
最终结果
控制指令
ros2 topic pub /forward_velocity_controller/commands std_msgs/msg/Float64MultiArray "{data: [-10,-10,-10,-10]}" --rate 100