PilzDE / pilz_robots

PILZ robot manipulator module PRBT 6 in ROS
https://wiki.ros.org/pilz_robots
50 stars 25 forks source link

Error after apending pg70 gripper #78

Closed CloudYin closed 5 years ago

CloudYin commented 5 years ago

Hello everyone,

after I added a gripper argument in my_application launch file (created during PRBT tutorial), an error and some warnings occurred during compilation.

[ERROR] [1551164434.657030599]: Joint 'prbt_gripper_finger_left_joint' declared as part of group 'gripper' is not known to the URDF [ WARN] [1551164434.660436207]: Group 'gripper' is empty. [ WARN] [1551164434.660658654]: Link 'prbt_gripper_finger_left_link' is not known to URDF. Cannot disable collisons.

Here is my launch file. add_gripper

Do I need to create new joint between pg70 and flange in the project urdf xacro file?

agutenkunst commented 5 years ago

You need to extend your xacro file to attach the gripper. It should look somewhat like this:

<?xml version="1.0" ?>

<robot name="prbt" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- Definition of robot name -->
  <xacro:arg name="robot_prefix" default="prbt_"/>

  <!-- macro definition of pilz lwa -->
  <xacro:include filename="$(find prbt_support)/urdf/prbt_macro.xacro" />

    <!-- gripper -->
  <xacro:arg name="gripper" default=""/>
  <xacro:property name="gripper" value="$(arg gripper)"/>

  <!-- TCP Offset -->
  <xacro:if value="${not gripper}">
    <xacro:arg name="tcp_offset_xyz" default="0 0 0"/>
    <xacro:arg name="tcp_offset_rpy" default="0 0 0"/>
  </xacro:if>

  <xacro:if value="${gripper != ''}">
    <xacro:include filename="$(find prbt_${gripper}_support)/config/${gripper}_tcp_offset.xacro" />
  </xacro:if>

  <!-- coloring from the stl file -->
  <material name="yellow">
    <color rgba="1 1 0 1"/>
  </material>

  <!-- coloring from the table -->
  <material name="grey">
    <color rgba="0.75 0.75 0.75 1"/>
  </material>

  <!-- instantiate the robot -->
  <xacro:prbt prefix="prbt_"/>

    <!-- TCP -->
  <joint name="$(arg robot_prefix)fixed_joint_tcp" type="fixed">
    <origin xyz="$(arg tcp_offset_xyz)" rpy="$(arg tcp_offset_rpy)" />  <!-- tcp offset from last link -->
    <parent link="$(arg robot_prefix)flange"/>
    <child link="$(arg robot_prefix)tcp"/>
  </joint>
  <link name="$(arg robot_prefix)tcp" />

  <!-- If gripper given then... -->
  <xacro:if value="${gripper != ''}">
    <xacro:include filename="$(find prbt_${gripper}_support)/urdf/${gripper}.urdf.xacro" />
  </xacro:if>

  <link name="table">
    <visual>
      <origin rpy="0 0 0" xyz="0 -0.45 -0.03"/>
      <geometry>
        <box size="0.6 1.2 0.05"/>
      </geometry>
      <material name="grey"/>
    </visual>
  </link>

  <link name="pnoz">
    <visual>
      <origin rpy="1.5708 0 0" xyz="0 -0.5 0"/>
      <geometry>
        <mesh filename="package://pilz_tutorial/urdf/meshes/PNOZ.stl"
          scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="yellow"/>
    </visual>
  </link>

  <joint name="table_joint" type="fixed">
    <parent link="table"/>
    <child link="prbt_base_link"/>
  </joint>

  <joint name="pnoz_joint" type="fixed">
    <parent link="table"/>
    <child link="pnoz"/>
  </joint>

</robot>

The launchfile should be:

<?xml version="1.0"?>
<launch>

  <arg name="sim" default="true" />
  <arg name="gripper" default="" />

  <!-- send urdf to param server -->
  <param name="robot_description"
    command="$(find xacro)/xacro --inorder '$(find pilz_tutorial)/urdf/my_first_application.xacro' gripper:=$(arg gripper)"/>

  <include file="$(find prbt_moveit_config)/launch/moveit_planning_execution.launch">
    <arg name="load_robot_description" value="false"/>
    <arg name="sim" value="$(arg sim)"/>
    <arg name="gripper" value="$(arg gripper)"/>
    <arg name="pipeline" value="pilz_command_planner"/>
  </include>

</launch>

Please post if this works for your

CloudYin commented 5 years ago

You need to extend your xacro file to attach the gripper. It should look somewhat like this: <?xml version="1.0" ?>

The launchfile should be: <?xml version="1.0"?>

Please post if this works for your

OK. Now it works perfectly. Thanks :-)