编写自己的机器人的模型URDF

   总之,最重要的一点是:每个部件的中点是相对于parent_frame父坐标系的几何中心的。尽管做出来的车有人说像充电宝,有人说是个滑板模型(笑哭无奈的表情哈!—)我还是要把它贴出来。

    代码如下:agvcar.urdf

<?xml version="1.0"?>
<robot name="agvcar">
  <link name="base_link">
    <visual>
      <geometry>
        <box size="1.46 0.45 0.08"/>
    </geometry>
    <origin rpy="0 0 1.57075" />
    <material name="yellow">
        <color rgba="1 0.4 0 1"/>
    </material>
    </visual>
 </link>

 <link name="front_wheel">
    <visual>
      <geometry>
        <cylinder length="0.058" radius="0.091"/>
      </geometry>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
    </visual>
  </link>

  <joint name="base_front_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="front_wheel"/>
    <origin rpy="0 1.57075 0" xyz="0.0 0.225 -0.04"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  <link name="right_back_wheel">
    <visual>
      <geometry>
        <cylinder length="0.04" radius="0.08"/>
      </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.187  -0.67 -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=".04" radius="0.08"/>
      </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.187  -0.67 -0.03"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  <link name="head">
    <visual>
      <geometry>
        <box size=".45 .045 .08"/>
      </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.73 0.0"/>
  </joint>
</robot>

base.urdf.rviz.launch使用RVIZ显示车体模型文件:

<launch>
    <arg name="model" />
    <arg name="gui" default="False" />
    <param name="robot_description" textfile="$(find agvcar_description)/urdf/agvcar.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" />

</launch>

 

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值