分别用urdf和xacro语法建立小车模型

1.文件目录

 

2.urdf

src/urdf01_rviz/urdf/urdf/demo05_test.urdf

<robot name="mycar">
    <!--1.添加 base_footprint-->
    <link name="base_footprint">
        <visual>
            <geometry>
                <sphere  radius="0.001" />
            </geometry>
        </visual>
    </link>

    <!--2.添加底盘 -->
    <!-- 
        参数
        形状:圆柱 
        半径:0.1m       10cm 
        高度:0.08m      8cm 
        离地:0.015m     1.5cm

    -->
    <!--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="base_link_color">
                <color rgba="1.0 0.5 0.2 0.5" />
            </material>
        </visual>
    </link>
    <!--2.2. joint-->
    <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.添加驱动轮 -->
    <!-- 
         驱动轮是侧翻的圆柱
        参数
            半径: 3.25 cm
            宽度: 1.5  cm
            颜色: 黑色
     -->
    <!--3.1.link-->
    <link name="left_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.0325" length="0.015" />
            </geometry>
            <!--关节之间的偏移由joint实现-->
            <origin  xyz="0  0  0" rpy="1.5708 0 0"/>

            <material name="left_wheel_color">
                <color rgba="0 0 0 0.3" />
            </material>
        </visual>
    </link>

    <link name="right_wheel">
        <visual>
            <geometry>
                <cylinder radius="0.0325" length="0.015" />
            </geometry>
            <!--关节之间的偏移由joint实现-->
            <origin  xyz="0  0  0" rpy="1.5708 0 0"/>

            <material name="rignt_wheel_color">
                <color rgba="0.8 0 0 0.3" />
            </material>
        </visual>
    </link>
    <!--3.2.joint-->
    <joint name="left2link"  type="continuous" >
        <parent link="base_link" />
        <child link="left_wheel" />
        <!--
           关节设置:
            x = 0  无偏移
            y = 底盘的半径 + 轮胎宽度 / 2  0.1 + 0.015/2= 0.1075 
            (但用了后,均设为0.1075,使用控制运动gui,画面会闪烁)(均设置为0.1 也会闪烁)
            (一个0.1075 ,一个0.1 ,不会闪烁)
            z = 离地间距 + 底盘长度 / 2 - 轮胎半径 = 1.5 + 4 - 3.25 = 2.25(cm)
            z=-0.0225  因为驱动轮中心点 在 车体中心点下方
            (z= 车体高度/2 + 离地间距 - 车轮半径 ) 
            axis = 0 1 0
        -->
        <origin xyz="0 0.1 -0.0255" rpy="0 0 0"/>
        <axis xyz="0 1 0"/>
    </joint>

    <joint name="right2link"  type="continuous" >
        <parent link="base_link" />
        <child link="right_wheel" />
        <!--
           关节设置:
            x = 0  无偏移
            y = 底盘的半径 + 轮胎宽度 / 2  右轮在y  反方向,y=-0.1
            z = 离地间距 + 底盘长度 / 2 - 轮胎半径 = 1.5 + 4 - 3.25 = 2.25(cm)
            z=-0.0225  因为驱动轮中心点 在 车体中心点下方
            axis = 0 1 0
        -->
        <origin xyz="0 -0.1 -0.0255" rpy="0 0 0"/>
        <axis xyz="0 1 0"/>
    </joint>
    <!--4.添加万向轮(支撑轮) -->
    <!-- 
         参数
            形状: 球体
            半径: 0.75 cm
            颜色: 黑色

        关节设置:
            x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
            y = 0
            z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475
            axis= 1 1 1

     -->
    <!--4.1.link-->
    <link name="front_wheel">
        <visual>
            <geometry>
                <sphere radius="0.0075" />
            </geometry>
            <!--关节之间的偏移由joint实现-->
            <origin  xyz="0  0  0" rpy="0 0 0"/>

            <material name="front_wheel_color">
                <color rgba="0 0 0 0.3" />
            </material>
        </visual>
    </link>

    <link name="back_wheel">
        <visual>
            <geometry>
                <sphere radius="0.0075" />
            </geometry>
            <!--关节之间的偏移由joint实现-->
            <origin  xyz="0  0  0" rpy="0 0 0"/>

            <material name="back_wheel_color">
                <color rgba="0.9 0 0 0.3" />
            </material>
        </visual>
    </link>
    <!--4.2.joint-->
    <joint name="front2link"  type="continuous" >
        <parent link="base_link" />
        <child link="front_wheel" />
        <!--
            关节设置:
            在车体x轴方向上,万向轮中心点一般位于车体半径范围内
            x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
            y = 0
            z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475 
            或 0.055(底盘中心点距离地面) - 0.0075(万向轮中心点距离地面) = 0.0475
            axis= 1 1 1
        -->
        <origin xyz="0.08 0 -0.0475" rpy="0 0 0"/>
        <axis xyz="1 1 1"/>
    </joint>

     <joint name="back2link"  type="continuous" >
        <parent link="base_link" />
        <child link="back_wheel" />
        <!--
            关节设置:
            在车体x轴方向上,万向轮中心点一般位于车体半径范围内
            x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
            y = 0
            z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475 
            或 0.055(底盘中心点距离地面) - 0.0075(万向轮中心点距离地面) = 0.0475
            axis= 1 1 1
        -->
        <origin xyz="-0.08 0 -0.0475" rpy="0 0 0"/>
        <axis xyz="1 1 1"/>
    </joint>
      
</robot>

src/urdf01_rviz/launch/demo05_test.launch

<launch>
    <!--1.将 urdf 文件内容设置进参数服务器 -->
    <param name="robot_description" textfile="$(find urdf01_rviz)/urdf/urdf/demo05_test.urdf" />

    <!--2.启动 rivz -->
    <node pkg="rviz" type="rviz" name="rviz_test" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />

    <!--3.添加机器人状态发布节点 -->
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
    <!--4.添加关节状态发布节点 -->
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" />

    <!--5.添加图形化的关节运动控制节点 -->
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />

</launch>

3.xacro

src/urdf01_rviz/urdf/xacro/demo05_car_base.urdf.xacro 

<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
    <xacro:property name="footprint_radius" value="0.001"/>
    <!--1.添加 base_footprint-->
    <link name="base_footprint">
        <visual>
            <geometry>
                <sphere  radius="${footprint_radius}" />
            </geometry>
        </visual>
    </link>
    

    <!--2.添加底盘 -->
    <!-- 
        参数
        形状:圆柱 
        半径:0.1m       10cm 
        高度:0.08m      8cm 
        离地:0.015m     1.5cm

    -->

    <xacro:property name="base_radius" value="0.1"/>
    <xacro:property name="base_length" value="0.08"/>
    <xacro:property name="lidi" value="0.015"/>
    <xacro:property name="base_joint_z" value="${base_length/2 + lidi}"/>

    <!--2.1.link-->
    <link name="base_link">
        <visual>
            <geometry>
                <cylinder radius="${base_radius}" length="${base_length}" />
            </geometry>

            <origin  xyz="0  0  0" rpy="0 0 0"/>

            <material name="base_link_color">
                <color rgba="1.0 0.5 0.2 0.5" />
            </material>
        </visual>
    </link>
    <!--2.2. joint-->
    <joint name="link2footprint"  type="fixed" >
        <parent link="base_footprint" />
        <child link="base_link" />
        <!--关节z上的设置 = 车体高度/2 + 离地间距-->
        <!--在z上的偏移量,base_link相对于base_footprint的偏移量-->
        <origin xyz="0 0 ${base_joint_z}" rpy="0 0 0"/>
    </joint>


    <!--3.添加驱动轮 -->
    <!-- 
         驱动轮是侧翻的圆柱
        参数
            半径: 3.25 cm
            宽度: 1.5  cm
            颜色: 黑色
     -->
    <!--属性-->
    <xacro:property name="wheel_radius" value="0.0325" />
    <xacro:property name="wheel_length" value="0.015" />
    <xacro:property name="PI" value="3.1415927" />
    <!--注意:结果是负数(驱动轮坐标原点在车体坐标原点z轴下方)-->
    <xacro:property name="wheel_joint_z" value="${(base_length / 2 + lidi - wheel_radius) *(-1) }" />
    
    <!--两个参数:
            wheel_name: left 或 right
            flag: 1 或 -1
    -->
    <xacro:macro  name="wheel_func" params="wheel_name flag">

        <!--3.1.link-->
        <link name="${wheel_name}_wheel">
            <visual>
                <geometry>
                    <cylinder radius="${wheel_radius}" length="${wheel_length}" />
                </geometry>
                <!--关节之间的偏移由joint实现-->
                <origin  xyz="0  0  0" rpy="${PI / 2} 0 0"/>

                <material name="wheel_color">
                    <color rgba="0 0 0 0.3" />
                </material>
            </visual>
        </link>

        
        <!--3.2.joint-->
        <joint name="${wheel_name}2link"  type="continuous" >
            <parent link="base_link" />
            <child link="${wheel_name}_wheel" />
            <!--
            关节设置:
                x = 0  无偏移
                y = 底盘的半径 + 轮胎宽度 / 2    0.1 + 0.015/2= 0.1075 
                z = 离地间距 + 底盘长度 / 2 - 轮胎半径   = 1.5 + 4 - 3.25 = 2.25(cm)
                z=-0.0225  因为驱动轮中心点 在 车体中心点下方
                (z= 车体高度/2 + 离地间距 - 车轮半径 ) 
                axis = 0 1 0
            -->
            <origin xyz="0 ${0.1 * flag} ${wheel_joint_z}" rpy="0 0 0"/>
            <axis xyz="0 1 0"/>
        </joint>

    </xacro:macro>

    <!--调用xacro宏 wheel_func -->
    <xacro:wheel_func wheel_name="left" flag="1" />
    <xacro:wheel_func wheel_name="right" flag="-1" />

   
    <!--4.添加万向轮(支撑轮) -->
    <!-- 
         参数
            形状: 球体
            半径: 0.75 cm  0.0075m
            颜色: 黑色

        关节设置:
            x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
            y = 0
            z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475
            
            z = 底盘高度 / 2 + 离地间距 - 万向轮半径 = 0.04 + 0.015 - 0.0075 = 0.0475 
            axis= 1 1 1
    -->

    <xacro:property name="small_wheel_radius" value="0.0075" />
    <xacro:property name="small_joint_x" value="0.08" />
    <!-- z的偏移量 : z = 底盘高度 / 2 + 离地间距 - 万向轮半径 = 0.04 + 0.015 - 0.0075 = 0.0475-->
    <xacro:property name="small_joint_z" value="${(base_length / 2 + lidi - small_wheel_radius) * (-1)}" />
    
    <xacro:macro name="small_wheel_func" params="small_wheel_name flag">
    <!--将下面变量置换为 宏的参数 small_wheel_name flag -->
        <!--4.1.link-->
        <link name="${small_wheel_name}_wheel">
            <visual>
                <geometry>
                    <sphere radius="${small_wheel_radius}" />
                </geometry>
                <!--关节之间的偏移由joint实现-->
                <origin  xyz="0  0  0" rpy="0 0 0"/>

                <material name="wheel_color">
                    <color rgba="0 0 0 0.3" />
                </material>
            </visual>
        </link>

        <!--4.2.joint-->
        <joint name="${small_wheel_name}2link"  type="continuous" >
            <parent link="base_link" />
            <child link="${small_wheel_name}_wheel" />
            <!--
                关节设置:
                在车体x轴方向上,万向轮中心点一般位于车体半径范围内
                x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
                y = 0
                z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475 
                或 0.055(底盘中心点距离地面) - 0.0075(万向轮中心点距离地面) = 0.0475
                axis= 1 1 1
            -->
            <origin xyz="${small_joint_x *flag} 0 ${small_joint_z}" rpy="0 0 0"/>
            <axis xyz="1 1 1"/>
        </joint>
    </xacro:macro>
    
    <xacro:small_wheel_func small_wheel_name="front" flag="1" />
    <xacro:small_wheel_func small_wheel_name="back" flag="-1" />

</robot>

src/urdf01_rviz/launch/demo06_car_base.launch 

 注意:

xacro集成在launch文件有两种方式,

1)先将xacro转换为urdf文件,然后使用textfile属性  解析urdf文件

2)直接解析xacro文件,使用command属性

xcaro功能包,xacro节点, xacro文件

command解析文件 并将解析内容加载至参数服务器

<launch>
    <!--1.将 urdf 文件内容设置进参数服务器 -->
    <!--方式1-->
    <!-- <param name="robot_description" textfile="$(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf" /> -->
    <!--方式2-->
    <param name="robot_description" command="$(find xacro)/xacro  $(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf.xacro" />
    
    <!--2.启动 rivz -->
    <node pkg="rviz" type="rviz" name="rviz_test" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />

    <!--3.添加机器人状态发布节点 -->
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
    <!--4.添加关节状态发布节点 -->
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" />

    <!--5.添加图形化的关节运动控制节点 -->
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />

</launch>

 

4.效果(rviz) 

参考资料:

 1.赵虚左老师ros1课程

6.4.3 Xacro_完整使用流程示例 · Autolabor-ROS机器人入门课程《ROS理论与实践》零基础教程

 

  • 4
    点赞
  • 6
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值