ROS探索总结-5.创建简单的机器人模型smartcar
创建简单的机器人模型smartcar
- 修改版:2016-10-13 by ncnynl
前面我们使用的是已有的机器人模型进行仿真,这一节我们将建立一个简单的智能车机器人smartcar,为后面建立复杂机器人打下基础。
urdf相关工具安装(补充)
- 安装urdf_tutorial,可以使用其中的例子
$ sudo apt-get install ros-indigo-urdf-tutorial
- 安装liburdfdom-tools,提供对urdf文件的检查
$ sudo apt-get install liburdfdom-tools
一、创建硬件描述包
$ roscreate-pkg smartcar_description
注意:上面方法旧了,indigo版本使用catkin_create_pkg创建包:
$ catkin_create_pkg smartcar_description std_msgs rospy roscpp urdf
二、智能车尺寸数据
因为建立的是一个非常简单的机器人,所以我们尽量使用简单的元素:使用长方体代替车模,使用圆柱代替车轮,具体尺寸如下:
三、建立urdf文件
在smartcar_description文件夹下建立urdf文件夹 $mkdir -p urdf
,创建智能车的描述文件smartcar.urdf,描述代码如下:
<?xml version="1.0"?>
<robot name="smartcar">
<link name="base_link">
<visual>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
<origin rpy="0 0 1.57075" xyz="0 0 0"/>
<material name="blue">
<color rgba="0 0 .8 1"/>
</material>
</visual>
</link>
<link name="right_front_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<joint name="right_front_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_front_wheel"/>
<origin rpy="0 1.57075 0" xyz="0.08 0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="right_back_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<joint name="right_back_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_back_wheel"/>
<origin rpy="0 1.57075 0" xyz="0.08 -0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="left_front_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<joint name="left_front_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_front_wheel"/>
<origin rpy="0 1.57075 0" xyz="-0.08 0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="left_back_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
</link>
<joint name="left_back_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_back_wheel"/>
<origin rpy="0 1.57075 0" xyz="-0.08 -0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="head">
<visual>
<geometry>
<box size=".02 .03 .03"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
</link>
<joint name="tobox" type="fixed">
<parent link="base_link"/>
<child link="head"/>
<origin xyz="0 0.08 0.025"/>
</joint>
</robot>
四、建立launch命令文件
在smartcar_description文件夹下建立launch文件夹mkdir -p launch
,创建智能车的描述文件 base.urdf.rviz.launch,描述代码如下:
<launch>
<arg name="model" />
<arg name="gui" default="False" />
<param name="robot_description" textfile="$(find smartcar_description)/urdf/smartcar.urdf" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find urdf_tutorial)/urdf.vcg" />
</launch>
注意:上面的launch已经旧了,indigo版本launch如下:
<launch>
<arg name="model" />
<arg name="gui" default="False" />
<param name="robot_description" textfile="$(find smartcar_description)/urdf/smartcar.urdf" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >
</node>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find urdf_tutorial)/urdf.rviz" />
</launch>
五、效果演示
在终端中输入显示命令:
roslaunch smartcar_description base.urdf.rviz.launch gui:=true
显示效果如下图所示,使用gui中的控制bar可以控制四个轮子单独旋转。
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号