参考视频:【奥特学园】ROS机器人入门课程《ROS理论与实践》零基础教程_哔哩哔哩_bilibili
参考文档:http://www.autolabor.com.cn/book/ROSTutorials/
需求描述:
创建一个四轮圆柱状机器人模型,机器人参数如下,底盘为圆柱状,半径 10cm,高 8cm,四轮由两个驱动轮和两个万向支撑轮组成,两个驱动轮半径为 3.25cm,轮胎宽度1.5cm,两个万向轮为球状,半径 0.75cm,底盘离地间距为 1.5cm(与万向轮直径一致)
结果演示:
实现流程:
创建机器人模型可以分步骤实现
-
新建 urdf 文件,并与 launch 文件集成
-
搭建底盘
-
在底盘上添加两个驱动轮
-
在底盘上添加两个万向轮
1.新建urdf以及launch文件
urdf 文件:基本实现
<robot name="mycar">
<!-- 设置 base_footprint -->
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="0.001" />
</geometry>
</visual>
</link>
<!-- 添加底盘 -->
<!-- 添加驱动轮 -->
<!-- 添加万向轮(支撑轮) -->
</robot>
launch 文件:
<launch>
<!--1.在参数服务器中载入urdf-->
<param name="robot_description" textfile="$(find urdf01_rviz)/urdf/urdf/demo05_test.urdf" />
<!--2.启动rviz-->
<node pkg="rviz" name="rviz" type="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz"/>
<!--3.关节状态发布节点-->
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher"/>
<!--4.机器人状态发布节点-->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/>
<!--5.添加控制关节运动的节点-->
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />
</launch>
2.底盘搭建
<robot name="mycar">
<!--1.添加 base_footprint-->
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="0.001"/>
</geometry>
</visual>
</link>
<!--2.添加地盘-->
<!--
形状:圆柱
半径:0.1m
高度:0.08m
离地间距:0.012m
-->
<!--2.1.link-->
<link name="base_link">
<visual>
<geometry>
<cylinder radius="0.1" length="0.08" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="baselink_color" >
<color rgba="1.0 0.5 0.2 0.5" />
</material>
</visual>
</link>
<!--2.2.join-->
<joint name="link2footprint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link" />
<!--关节z上的设置 = 车体高度/2 + 离地间距-->
<origin xyz="0 0 0.055" rpy="0 0 0" />
</joint>
<!--3.添加驱动轮-->
<!--4.添加万向轮-->
</robot>
两个link之间的相对偏移量建议写在 joint 的 origin 里 ,方便各组件之间距离换算

3.添加驱动轮
<!--3.添加驱动轮-->
<!--
形状:圆柱
半径:0.035m
长度:0.015m
-->
<!--3.1.link-->
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.0325" length="0.015" />
</geometry>
<origin xyz="0 0 0" rpy="1.5708 0 0" />
<material name="leftwheel_color" >
<color rgba="0 1.0 0 0.3" />
</material>
</visual>
</link>
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.0325" length="0.015" />
</geometry>
<origin xyz="0 0 0" rpy="1.5708 0 0" />
<material name="rightwheel_color" >
<color rgba="0 1.0 0 0.3" />
</material>
</visual>
</link>
<!--3.2.join-->
<joint name="left2footprint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel" />
<!--
x 无偏移
y 车体半径
z z = 车体高度 / 2 + 离地间距 - 车轮半径
-->
<origin xyz="0 0.1 -0.0225" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="right2footprint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel" />
<!--
x 无偏移
y 车体半径
z z = 车体高度 / 2 + 离地间距 - 车轮半径
-->
<origin xyz="0 -0.1 -0.0225" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
4.添加万向轮
<!--4.添加万向轮-->
<!--
形状:球
半径:0.0075m
-->
<!--4.1.link-->
<link name="front_wheel">
<visual>
<geometry>
<sphere radius="0.0075" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="frontwheel_color" >
<color rgba="0 0 1 0.3" />
</material>
</visual>
</link>
<link name="back_wheel">
<visual>
<geometry>
<sphere radius="0.0075" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="backwheel_color" >
<color rgba="0 0 1 0.3" />
</material>
</visual>
</link>
<!--4.2.joint-->
<joint name="front2footprint" type="continuous">
<parent link="base_link"/>
<child link="front_wheel" />
<origin xyz="0.08 0 -0.0475" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
<joint name="back2footprint" type="continuous">
<parent link="base_link"/>
<child link="back_wheel" />
<origin xyz="-0.08 0 -0.0475" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
所有评论(0)