瞬驰(Dash)D1开发手册--URDF

创建URDF文件,就可以在rviz中实时观测底盘的移动。

创建包

cd ~/catkin_ws/src
catkin_create_pkg dash_describe std_msgs rospy roscpp

urdf文件

在urdf/dashbase目录下需要创建如下文件:

  • materials.urdf.xacro 颜色属性
<?xml version="1.0"?>
<robot>

  <!-- Put all the color definitions in a separate file -->

  <material name="Black">
    <color rgba="0.2 0.2 0.2 1.0"/>
  </material>

   <material name="TransparentBlack">
    <color rgba="0.2 0.2 0.2 0.8"/>
  </material>

  <material name="Orange">
    <color rgba="1.0  0.55 0.0 1.0"/>
  </material>

  <material name="Grey">
    <color rgba="0.7 0.7 0.7 1.0"/>
  </material>

  <material name="DarkGrey">
    <color rgba="0.3 0.3 0.3 1.0"/>
  </material>

  <material name="Red">
    <color rgba="0.8 0.0 0.0 1.0"/>
  </material>

  <material name="White">
    <color rgba="1.0 1.0 1.0 1.0"/>
  </material>

  <material name="OffWhite">
    <color rgba="0.8 0.8 0.8 1.0"/>
  </material>

  <material name="Blue">
    <color rgba="0.0 0.0 0.8 1.0"/>
  </material>

  <material name="Green">
    <color rgba="0.0 0.8 0.0 1.0"/>
  </material>

  <material name="TransparentGreen">
    <color rgba="0.0 0.8 0.0 0.5"/>
  </material>

</robot>
  • 底盘和轮子的定义 base.urdf.xacro
<?xml version="1.0"?>
<robot name="base" xmlns:xacro="http://ros.org/wiki/xacro">

  <!-- Define a number of dimensions using properties -->
  <property name="base_length" value="0.165" />
  <property name="base_radius" value="0.20" />
  <property name="wheel_length" value="0.02" />
  <property name="wheel_radius" value="0.060" />
  <property name="wheel_offset_x" value="0" />
  <property name="wheel_offset_y" value="0.17" />
  <property name="wheel_offset_z" value="-0.038" />

  <property name="PI" value="3.1415926" />

  <!-- define a wheel -->
  <macro name="wheel" params="suffix parent reflect color">
    <joint name="${parent}_${suffix}_wheel_joint" type="continuous">
      <axis xyz="0 0 1" />
      <limit effort="100" velocity="100"/>
      <safety_controller k_velocity="10" />
      <origin xyz="${wheel_offset_x} ${reflect*wheel_offset_y} ${wheel_offset_z}" rpy="${reflect*PI/2} 0 0" />
      <parent link="${parent}_link"/>
      <child link="${parent}_${suffix}_wheel_link"/>
    </joint>
    <link name="${parent}_${suffix}_wheel_link">
<!--
 <visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://common/urdf/meshes/wheel.STL" />
      </geometry>
      <material name="${color}" />
</visual>
-->
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <cylinder radius="${wheel_radius}" length="${wheel_length}"/>
        </geometry>
        <material name="${color}" />
      </visual>
    </link>
  </macro>

  <!-- The base xacro macro -->
  <macro name="base" params="name color">
    <link name="${name}_link">
<!--
 <visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://common/urdf/meshes/dash_base_all.STL" />
      </geometry>
      <material name="">        
        <color
          rgba="255 215 0 0.5"/>
      </material>
</visual>
-->
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <cylinder length="${base_length}" radius="${base_radius}"/>
            </geometry>
            <material name="iRobot/LightGrey"/>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <cylinder length="${base_length}" radius="${base_radius}"/>
            </geometry>
        </collision>
    </link>
  </macro>

  <link name="base_footprint">
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <box size="0.05 0.05 0.001" />
        </geometry>
        <material name="TransparentGreen" />
      </visual>
  </link>

  <joint name="base_joint" type="fixed">
    <origin xyz="0 0 ${base_length/2 - wheel_offset_z}" rpy="0 0 0" />      
    <parent link="base_footprint"/>
    <child link="base_link" />
  </joint>

   <!-- Add the drive wheels -->
   <wheel parent="base" suffix="l" reflect="1" color="Orange"/>
   <wheel parent="base" suffix="r" reflect="-1" color="Orange"/>

</robot>
  • 整体: dashbase.urdf
<?xml version="1.0"?>

<robot name="box_robot" xmlns:xacro="http://ros.org/wiki/xacro">
   <!-- Include all component files -->
   <xacro:include filename="$(find dash_describe)/urdf/dashbase/materials.urdf.xacro" />
   <xacro:include filename="$(find dash_describe)/urdf/dashbase/base.urdf.xacro" />
   <!-- Add the base and wheels -->
   <base name="base" color="Black"/>

</robot>

launch

创建 launch/dash_describe.launch,内容如下:

<launch>
    <!-- Load the URDF/Xacro model of our robot -->
    <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find dash_describe)/urdf/dashbase/dashbase.xacro'" />

    <param name="robot_description" command="$(arg urdf_file)" />

    <!-- Publish the robot state -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">
        <param name="publish_frequency" value="20.0"/>
    </node>

    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
        <param name="rate" value="20.0"/>
    </node>
</launch>

启动命令

在一个终端执行

roslaunch dash_describe dash_describe.launch

在另一个终端执行

rviz

在rviz界面, Global Options->Fixed Color 选择”base_footprint”, 点击左下部”Add”按钮,选择”RobotModel“。
然后就可以看到我们创建的小车底盘了。

注意:如果在raspberry Pi下运行, rviz运行不了。

raspberry pi运行方法

需要raspberry pi和电脑配合使用。首先在/etc/hosts中相互添加对方的hostname和ip

然后, 在raspberry Pi执行如下语句

roslaunch dash_describe dash_describe.launch

在电脑的同一个终端先后执行如下命令。

export ROS_MASTER_URI=http://RaspberryPi的ip:11311

然后执行rviz

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值