阿克曼结构移动机器人的gazebo仿真(四)
第四章、手撸阿克曼小车URDF代码
0.前言
上节说道通过twist消息控制从solidworks导出的阿克曼小车,但后续的开发工作中发现了从SW导出的模型做仿真有一些弊端,导致仿真的效果并不理想,所以博主准备手写一个urdf代码,并通过模型替代法来实现tianracer的仿真,本次写的urdf文件是基于tianracer小车1:1比例来编写的,方便后续的模型替换工作。
1.创建小车功能包
在工作空间内创建racebot_description功能包
catkin_create_pkg racebot_description roscpp rospy std_msgs
在该工作空间下创建config、launch、rviz_config、scripts、urdf等文件夹,此时准备工作已经做完。
2.配置创建环境
我们需要创建一个URDF文件与能让模型在rviz中显示的launch文件,方便我们创造模型。以创建小车base_link模型为例:
在urdf文件夹中创建racebot.urdf文件,首先创建base_link,由于根link不能包含碰撞属性,否则gazebo仿真中会报错,所以我们将base_footprint作为根link,并且将base_footprint设置为小车贴到地面的位置,由于该小车是1:1仿真tianracer的,所以base_link在base_footprint正上方32mm处,如下代码所示:
<?xml version="1.0" encoding="utf-8"?>
<robot name="racebot">
<link name="base_footprint">
</link>
<link name="base_link">
<visual>
<geometry>
<box size="0.28 0.1 0.03"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.8 0.3 0.1 0.5" />
</material>
</visual>
<collision>
<geometry>
<box size="0.28 0.1 0.03" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
</link>
<joint name="base_link_joint" type="fixed">
<parent link="base_footprint" />
<child link="base_link"/>
<origin xyz="0 0 0.032" rpy="0 0 0" />
</joint>
</robot>
接着在launch文件夹中创建一个可以将小车模型在rviz中显示的launch文件racebot_rviz.launch,并且能够加载上述urdf文件:
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!-- 将 urdf 文件内容设置进参数服务器 -->
<param name="robot_description" textfile="$(find racebot_description)/urdf/racebot.urdf" />
<!-- 启动 rivz -->
<!-- <node pkg="rviz" type="rviz" name="rviz_test" args="-d $(find racebot_description)/config/racebot.rviz" /> -->
<node pkg="rviz" type="rviz" name="rviz" args="" />
<!-- 启动机器人状态和关节状态发布节点 -->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" />
<!-- 启动图形化的控制关节运动节点 -->
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />
</launch>
此时我们运行该launch文件:
roslaunch racebot_description racebot_rviz.launch
添加RobotModel插件,并将fixed frame改为base_footprint,此时我们便能在rviz中看到一个漂浮在空中的橙色方块,此为小车模型的base_link:
点击FILE–save config as选择racebot_description/rviz_config路径保存为racecar.rviz,并在launch中启动rviz节点时加载该配置文件,以便后续的开发。
3.添加前轮摆转以及前后轮
添加左前轮以及左前轮摆转
在阿克曼仿真第一节的时候了解到要使前轮转向,以左前轮为例,需要给左前轮加一个绕Z轴转动的自由度,因此需要添加一个能够摆转的link,将其命名为steering_hinge,前轮通过与其连接能够实现绕Z轴转动,joint_type设置为revolute,转动幅度设置为-0.6rad–0.6rad,effort与velocity分别设置为50,1000以方便后续控制。
<link name="left_steering_hinge">
<visual>
<geometry>
<cylinder radius="0.01" length="0.005" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.005" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.5" />
<inertia ixx="1.35E-05" ixy="0" ixz="0" iyy="1.35E-05" iyz="0" izz="2.5E-05" />
</inertial>
</link>
<joint name="left_steering_hinge_joint" type="revolute">
<parent link="base_link" />
<child link="left_steering_hinge" />
<origin xyz="0.13 0.065 0" />
<axis xyz="0 0 1" />
<limit lower="-0.6" upper="0.6" effort="5.0" velocity="1000.0"/>
</joint>
<link name="left_front_wheel">
<visual>
<geometry>
<cylinder radius="0.033" length="0.02" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.032" length="0.02" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.0" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="left_front_wheel_joint" type="continuous">
<parent link="left_steering_hinge" />
<child link="left_front_wheel" />
<origin xyz="0 0.025 0" />
<axis xyz="0 1 0" />
<limit effort="10" velocity="1000" />
</joint>
左前轮配置好了以后,右前轮同理,值得注意的是需要修改joint标签内的origin标签,可以大致理解为左前轮在第一象限,右前轮为第四象限,X轴正方向为小车的前进方向。在配置URDF的时候,若仅仅是想要在RVIZ中观察编写的模型情况,可以在link标签中,先不需要编写collision标签,编写collision时需要计算该link的惯性矩阵参数,会较为繁琐,可以在确定模型装配情况后最后编写collision标签。计算惯性矩阵的方法如下:
关于URDF中的惯性矩阵描述问题
配置后轮
前轮配置完成后,配置后轮,以左后轮为例,代码如下,右后轮同理:
<link name="left_rear_wheel">
<visual>
<geometry>
<cylinder radius="0.032" length="0.02" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.032" length="0.02" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.0" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="left_rear_wheel_joint" type="continuous">
<parent link="base_link" />
<child link="left_rear_wheel" />
<origin xyz="-0.13 0.09 0" />
<axis xyz="0 1 0" />
<limit effort="10" velocity="1000" />
</joint>
3.配置传感器
tianracer小车共有三样传感器,分别为单目相机,深度相机以及激光雷达,当然可以加入imu模块以作后备,这些link的装配都是相对固定的,因此惯性参数对其无太大影响,可以取一个大致值:
配置单目相机:
<link name="camera">
<visual>
<geometry>
<box size="0.005 0.03 0.03"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<box size="0.005 0.03 0.03"/>
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.05" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="camera_joint" type="fixed">
<parent link="base_link" />
<child link="camera" />
<origin xyz="0.14851 0.0022137 0.0975" />
<axis xyz="0 0 1" />
</joint>
配置深度相机:
<link name="real_sense">
<visual>
<geometry>
<box size="0.01 0.1 0.02"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<box size="0.01 0.1 0.02"/>
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.05" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="realsense_joint" type="fixed">
<parent link="base_link" />
<child link="real_sense" />
<origin xyz="0.19864 0.0038046 0.052021" />
<axis xyz="0 0 1" />
</joint>
配置单线激光雷达:
<link name="lidar">
<visual>
<geometry>
<cylinder radius="0.03" length="0.06" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.03" length="0.06" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.1" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="lidar_joint" type="fixed">
<parent link="base_link" />
<child link="lidar" />
<origin xyz="0.093603 0 0.12377" />
<axis xyz="0 0 1" />
</joint>
配置imu模块:
<link name="imu">
<visual>
<geometry>
<box size="0.01 0.01 0.005"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<box size="0.01 0.01 0.005"/>
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.05" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link" />
<child link="imu" />
<origin xyz="0 0 0.02" />
<axis xyz="0 0 1" />
</joint>
此时,小车URDF已经配置完成了,可以在rviz中观察模型效果:
小结
至此,已经将小车的URDF代码书写完毕,下一节将URDF优化为xacro,并加入传感器插件,以及小车轮子的传动。
参考资料
1.古月老师的<<ROS机器人开发实践>>
2.关于URDF中的惯性矩阵描述问题
|