文章目录

 
  • 介绍
  • minitaur urdf解析
    • base_chassis_link
    • chassis right
    • motor
    • upper_leg
    • lower_leg
  • 注意
 

介绍

  URDF全称为Unified Robot Description Format,中文可以翻译为“统一机器人描述格式”。与计算机文件中的.txt文本格式、.jpg图像格式等类似,URDF是一种基于XML规范、用于描述机器人结构的格式。根据该格式的设计者所言,设计这一格式的目的在于提供一种尽可能通用(as general as possible)的机器人描述规范。URDF创造的机器人模型包含的内容有:  
  • 连杆 link
  • 关节 joint
  • 运动学参数 axis
  • 动力学参数 dynamics
  • 可视化模型 visual
  • 碰撞检测模型 collision
 

minitaur urdf解析

 

base_chassis_link

 
<link name="base_chassis_link">
	<!--物理型状-->
	<visual>..第一个长方体.</visual>
	<visual>..2..</visual>
	<visual>..3..</visual>
	<!-- 设置碰撞-->
	<collision>...</collision>
	<collision>...</collision>
	<collision>...</collision>
	<!--设置属性例如质量,惯量-->
	<inertial>...</inertial>
</link>

  效果如下:   base  

chassis right

 
<link name="chassis_right">
	<!--motor支架-->
    <visual> .... </visual>
    <visual>.... </visual>
    
    <collision> </collision>
    <collision> ....</collision>
    <inertial>.... </inertial>
  </link>
  要添加一个joint约束位置,不然会报错  
<joint name="chassis_right_center" type="fixed">
    <axis xyz="0 0 1"/>
    <parent link="base_chassis_link"/>
    <child link="chassis_right"/>
    <origin rpy="-0.0872665 0 0" xyz="0.0 -0.10 0.0"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>
  chassis right   chassis left 同理   chassis left  

motor

 
<link name="motor_front_rightR_link">
    <visual>
      <geometry>
        <mesh filename="tmotor3.obj" scale="1 1 1"/>
      </geometry>
      <material name="white">
        <color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.026" radius="0.0434"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.25"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link> 

 
<joint name="motor_front_rightR_joint" type="continuous">
<axis xyz="0 0 1"/>
    <parent link="chassis_right"/>
    <child link="motor_front_rightR_link"/>
    <origin rpy="1.57075 0 0" xyz="0.21 -0.025 0"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>
  上述为右边电机,其余位置安装同理   在这里插入图片描述  

upper_leg

 
<link name="upper_leg_front_rightR_link">
    <visual>
      <geometry>
        <box size=".01 0.01 .11"/>
      </geometry>
      <material name="grey">
        <color rgba="0.65 0.65 0.75 1"/>
      </material>
    </visual>
    <collision>
      <geometry>
        <box size=".01 0.01 .11"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.05"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  注意对于upper_leg左右关节命名不一样,但其实是同一类型关节,这里涉及到minitaur仿真环境中的一些设置  
  <joint name="hip_front_rightR_link" type="fixed">
    <axis xyz="0 0 1"/>
    <parent link="motor_front_rightR_link"/>
    <child link="upper_leg_front_rightR_link"/>
    <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

 
<joint name="motor_front_rightL_link" type="fixed">
    <axis xyz="0 0 1"/>
    <parent link="motor_front_rightL_link"/>
    <child link="upper_leg_front_rightL_link"/>
    <origin rpy="-1.57075 0 0" xyz="0.0 0.06 -0.015"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

lower_leg

 
<link name="lower_leg_front_rightR_link">
	<contact>
		<stiffness value="10000"/>
		<damping value="10"/>
		<lateral_friction value="1"/>
  </contact>

    <visual>
    	<origin rpy="0.0 0 0" xyz="0 0 .1"/>
      <geometry>
        <box size=".01 0.01 .2"/>
      </geometry>
      <material name="grey">
        <color rgba="0.65 0.65 0.75 1"/>
      </material>
    </visual>
    <collision>
    	<origin rpy="0.0 0 0" xyz="0 0 .1"/>
      <geometry>
        <box size=".01 0.01 .2"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.05"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
  </link>

  lower_leg的关节以knee开头命名,joint类型为revolute的需要加入限制,不加模型会报错  
  <joint name="knee_front_rightR_link" type="revolute">
    <axis xyz="0 1 0"/>
    <parent link="upper_leg_front_rightR_link"/>
    <child link="lower_leg_front_rightR_link"/>
    <origin rpy="0 0 0" xyz="0.0 0.01 .055"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  leg  

注意

  link和joint都配置好后大概就是这个四脚朝天的样子了(图一),但是建模其实还没有完成,因为各个关节都是开环的(不是并联机构),简单来说就是这时候的minitaur足端是分离的(图二)   urdf部分的使命已经结束了,并联机构部分我们需要在bullet里面添加约束才能实现,使用createConstraint()  
self._pybullet_client.createConstraint(
          self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_link"],
          self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_link"],
          self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_RIGHT,
          KNEE_CONSTRAINT_POINT_LEFT)

  在这里插入图片描述  
图一
在这里插入图片描述