ROS漫漫长路(一)——Gazebo中机器人圆柱,球,长方体惯性矩阵推导与代码实现

ROS漫漫长路(一)——Gazebo中机器人圆柱,球,长方体惯性矩阵推导与代码实现


前言

ROS中,要想将urdf文件实现的机器人,放到gazebo中仿真,需要添加collision碰撞参数和inertial参数,其中collision参数大多情况下就直接和机器人的形状一致,而inertial则为机器人的惯性矩阵参数,基本构造机器人,常用的形状即为圆柱,球和长方体,即使是不规则的形状,推导方式其实也是一样的。

一、公式推导

 

 

 

 

 

 

 

 一、代码实现

ros中这部分的代码实现,其实直接使用官方给的就好了,在编写inertial参数时,分别调用sphere_inertial_matrix, cylinder_inertial_matrix, Box_inertial_matrix宏即可

 <xacro:Box_inertial_matrix m="" w="" l="" h=""/>   调用长方体
 <xacro:sphere_inertial_matrix m="" r="" /> 调用球
 <xacro:cylinder_inertial_matrix m="" r="" h="" /> 调用圆柱体

 示例

假如我要创建一个圆柱体的机器人

第一步把这个官方的惯性矩阵写道一个xacro文件中

<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- Macro for inertia matrix -->
    <xacro:macro name="sphere_inertial_matrix" params="m r">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
                iyy="${2*m*r*r/5}" iyz="0" 
                izz="${2*m*r*r/5}" />
        </inertial>
    </xacro:macro>

    <xacro:macro name="cylinder_inertial_matrix" params="m r h">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
                iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
                izz="${m*r*r/2}" /> 
        </inertial>
    </xacro:macro>

    <xacro:macro name="Box_inertial_matrix" params="m l w h">
       <inertial>
               <mass value="${m}" />
               <inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
                   iyy="${m*(w*w + l*l)/12}" iyz= "0"
                   izz="${m*(w*w + h*h)/12}" />
       </inertial>
   </xacro:macro>
</robot>

 第二步,在编写机器人xacro文件时,调用宏

 <link name="base_link">
      <visual>
        <geometry>
          <cylinder radius="0.1" length="0.05" />
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <material name="yellow">
          <color rgba="0.5 0.3 0.0 0.5" />
        </material>
      </visual>
      <collision>
        <geometry>
          <cylinder radius="0.1" length="0.05" />
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0" />
      </collision>
      <!--    调用宏来创建惯性矩阵    -->
      <xacro:cylinder_inertial_matrix m="1" r="0.1" h="0.05" />

    </link>

Guess you like

Origin blog.csdn.net/lzzzzzzm/article/details/119899598