0
$\begingroup$

Rosanswers logo

Hey friends,

I have a custom 4DOF arm I have whipped up and have been slogging through the tutorials but I feel like I am getting turned around easily now.

I am running Kinetic on Ubuntu 16.04 and have my Rviz and Moveit! setup working nicely. It can take plans and execute them as well as work quite nicely with my move group python interface. I have used the MSA to setup my Moveit files, and now would like to simulate my movements in gazebo and eventually tie in the custom arm.

My issue pops up when trying to run the files that were created by the MSA. Running demo_gazebo.launch from /arm_moveit_config yields this error:

[ERROR] [1588933219.280616367]: Failed to build tree: child link [base_link] of joint [dummy_joint] not found
[ERROR] [1588933219.518289973]: Failed to build tree: child link [base_link] of joint [dummy_joint] not found
[ERROR] [1588933219.520045115]: Unable to parse URDF from parameter '/robot_description'
[robot_state_publisher-7] process has died [pid 17994, exit code 255, cmd /opt/ros/kinetic/lib/robot_state_publisher/robot_state_publisher __name:=robot_state_publisher __log:=/home/homefolder/.ros/log/83c0a11e-9115-11ea-ad2a-001c429fcd02/robot_state_publisher-7.log].
log file: /home/homefolder/.ros/log/83c0a11e-9115-11ea-ad2a-001c429fcd02/robot_state_publisher-7*.log
[robot_state_publisher-7] restarting process
process[robot_state_publisher-7]: started with pid [18108]

Which continues to repeat until the program is killed. The Rviz and Gazebo windows pop up, but the model does not appear and they both show signs of error. After killing the program, there is also a warning that pops up before it dies:

[WARN] [1588933243.186197, 20.019000]: Controller Spawner couldn't find the expected controller_manager ROS interface.

Which I am unsure is a contributing factor to the first errors, or a product of them.

I have included my arm.xacro file below as well the launch file I am attempting to call.

Any suggestions or help is greatly appreciated.

m

arm.xacro

<?xml version="1.0"?>

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

   <xacro:include filename="$(find version1_desc)/urdf/links_joints.xacro" />
   <xacro:include filename="$(find version1_desc)/urdf/arm.gazebo" />
   <create/>
   <gazebo>
     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
       <robotNamespace>/arm</robotNamespace>
     </plugin>
   </gazebo>

<!--Dummy Link-->
    <link name="dummy_link"/>

<!-- Dummy End Effector -->
    <joint name="dummy_joint" type="fixed">
        <parent link="dummy_link"/>
        <child link="base_link"/>
      </joint>

<!--Base Link-->

    <m_link_mesh_c name = "base_link"
                     origin_rpy = "0 0 0" origin_xyz = "0 0 0" mass = "1.0"
                     meshfile = "package://version1_desc/meshes/base_link.dae"
                     meshscale  = "1 1 1"
                     ixx = "0.00153508333333" ixy = "0" ixz = "0" iyz = "0"
                     iyy = "0.00153508333333"
                     izz = "0.00245"
                     radius = "0.07" length= "0.061"/>

<!--Plat Joint-->

    <joint name="plat_joint" type="revolute">
        <parent link="base_link"/>
        <child link="plat_link"/>
        <origin rpy="0 0 0" xyz="0 0 0.0305"/>
        <limit lower="-1.5" upper="1.5" effort="1000" velocity="0.5"/>
        <axis xyz="0 0 1"/>
    </joint>

    <transmission name = "trans_plat">
        <type> transmission_interface/SimpleTransmission</type>
        <joint name= "plat_joint">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        </joint>
        <actuator name = "motor_plat">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

<!--Plat Link-->

    <m_link_mesh_c name = "plat_link"
                     origin_rpy = "0 0 0" origin_xyz = "0 0 0.004" mass = "0.072"
                     meshfile = "package://version1_desc/meshes/plat_link.dae"
                     meshscale  = "1 1 1"
                     ixx = "6.5184e-05" ixy = "0" ixz = "0" iyz = "0"
                     iyy = "6.5184e-05"
                     izz = "0.0001296"
                     radius = "0.06" length = "0.008"/>

<!--Lock Joint-->

    <joint name="lock_joint" type="fixed">
        <parent link="plat_link"/>
        <child link="lock_link"/>
        <origin rpy="0 0 0" xyz="0 0 0.004"/>
        <limit lower="-1.5" upper="1.5" effort="0.1" velocity="0.5"/>
        <axis xyz="0 0 1"/>
    </joint>

<!--Lock Link-->

    <m_link_mesh_b name = "lock_link"
                origin_rpy = "0 0 0" origin_xyz = "0 0 0.0185" mass = "0.001"
                meshfile = "package://version1_desc/meshes/lock_link.dae"
                meshscale  = "1 1 1"
                ixx = "3.66166666667e-07" ixy = "0" ixz = "0" iyz = "0"
                iyy = "1.47416666667e-07"
                izz = "2.85416666667e-07"
                size="0.02 0.055 0.037"/>

<!--Shoulder Joint-->

    <joint name="shoulder_joint" type="revolute">
        <parent link="lock_link"/>
        <child link="shoulder_link"/>
        <origin rpy="0 0 0" xyz="0 0 0.0265"/>
        <limit lower="-1.5" upper="1.5" effort="1000" velocity="0.5"/>
        <axis xyz="0 1 0"/>
    </joint>

    <transmission name = "trans_shoulder">
        <type> transmission_interface/SimpleTransmission</type>
        <joint name= "shoulder_joint">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        </joint>
        <actuator name = "motor_shoulder">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

<!--Shoulder Link-->

    <m_link_mesh_b name = "shoulder_link"
                origin_rpy = "0 0 0" origin_xyz = "0 0 0.098" mass = "0.163"
                meshfile = "package://version1_desc/meshes/shoulder_link.dae"
                meshscale  = "1 1 1"
                ixx = "0.000700302333333" ixy = "0" ixz = "0" iyz = "0"
                iyy = "0.000639177333333"
                izz = "7.19916666667e-05"
                size="0.02 0.07 0.216"/>

<!--Forearm Joint-->

    <joint name="forearm_joint" type="revolute">
        <parent link="shoulder_link"/>
        <child link="forearm_link"/>
        <origin rpy="0 0 0" xyz="0 0 0.191"/>
        <limit lower="-2.5" upper="2.5" effort="0" velocity="0.5"/>
        <axis xyz="0 1 0"/>
    </joint>

    <transmission name = "trans_forearm">
        <type> transmission_interface/SimpleTransmission</type>
        <joint name= "forearm_joint">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        </joint>
        <actuator name = "motor_forearm">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

<!--Forearm Link-->

    <m_link_mesh_b name = "forearm_link"
                origin_rpy = "0 0 0" origin_xyz = "0 0 0.055" mass = "0.217"
                meshfile = "package://version1_desc/meshes/forearm_link.dae"
                meshscale  = "1 1 1"
                ixx = "0.000471975" ixy = "0" ixz = "0" iyz = "0"
                iyy = "0.00042315"
                izz = "8.1375e-05"
                size="0.03 0.06 0.150"/>

<!--Wrist Joint-->

    <joint name="wrist_joint" type="revolute">
        <parent link="forearm_link"/>
        <child link="wrist_link"/>
        <origin rpy="0 0 0" xyz="0 0 0.110"/>
        <limit lower="-2.5" upper="2.5" effort="1000" velocity="0.5"/>
        <axis xyz="0 1 0"/>
    </joint>

    <transmission name = "trans_wrist">
        <type> transmission_interface/SimpleTransmission</type>
        <joint name= "wrist_joint">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        </joint>
        <actuator name = "motor_wrist">
            <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>

<!--Wrist Link-->

    <m_link_mesh_b name = "wrist_link"
                origin_rpy = "0 0 0" origin_xyz = "0 0 0.045" mass = "0.057"
                meshfile = "package://version1_desc/meshes/wrist_link.dae"
                meshscale  = "1 1 1"
                ixx = "9.1675e-05" ixy = "0" ixz = "0" iyz = "0"
                iyy = "7.03e-05"
                izz = "2.5175e-05"
                size="0.02 0.07 0.120"/>

<!-- Dummy End Effector -->
    <link name="dummy_eef"/>

<!-- Dummy End Effector -->
    <joint name="eef_joint" type="fixed">
        <parent link="wrist_link"/>
        <child link="dummy_eef"/>
      </joint>

</robot>

demo_gazebo.launch

<launch>

  <!-- By default, we do not start a database (it can be large) -->
  <arg name="db" default="false" />
  <!-- Allow user to specify database location -->
  <arg name="db_path" default="$(find arm_moveit_config)/default_warehouse_mongo_db" />

  <!-- By default, we are not in debug mode -->
  <arg name="debug" default="false" />

  <!--
  By default, hide joint_state_publisher's GUI

  MoveIt!'s "demo" mode replaces the real robot driver with the joint_state_publisher.
  The latter one maintains and publishes the current joint configuration of the simulated robot.
  It also provides a GUI to move the simulated robot around "manually".
  This corresponds to moving around the real robot without the use of MoveIt.
  -->
  <arg name="use_gui" default="false" />

  <!-- Gazebo specific options -->
  <arg name="gazebo_gui" default="true"/>
  <arg name="paused" default="false"/>
  <!-- By default, use the urdf location provided from the package -->
  <arg name="urdf_path" default="$(find version1_desc)/urdf/arm.xacro"/>

  <!-- launch the gazebo simulator and spawn the robot -->
  <include file="$(find arm_moveit_config)/launch/gazebo.launch" >
    <arg name="paused" value="$(arg paused)"/>
    <arg name="gazebo_gui" value="$(arg gazebo_gui)"/>
    <arg name="urdf_path" value="$(arg urdf_path)"/>
  </include>

  <!-- Load the URDF, SRDF and other .yaml configuration files on the param server -->
  <include file="$(find arm_moveit_config)/launch/planning_context.launch">
    <arg name="load_robot_description" value="false"/>
  </include>

  <!-- If needed, broadcast static tf for robot root -->
  

  <!-- We do not have a robot connected, so publish fake joint states -->
  <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    <param name="use_gui" value="$(arg use_gui)"/>
    <rosparam param="source_list">[/joint_states]</rosparam>
  </node>

  <!-- Given the published joint states, publish tf for the robot links -->
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" />

  <!-- Run the main MoveIt! executable without trajectory execution (we do not have controllers configured by default) -->
  <include file="$(find arm_moveit_config)/launch/move_group.launch">
    <arg name="allow_trajectory_execution" value="true"/>
    <arg name="fake_execution" value="false"/>
    <arg name="info" value="true"/>
    <arg name="debug" value="$(arg debug)"/>
  </include>  

  <!-- Run Rviz and load the default config to see the state of the move_group node -->
  <include file="$(find arm_moveit_config)/launch/moveit_rviz.launch">
    <arg name="config" value="true"/>
    <arg name="debug" value="$(arg debug)"/>
  </include>

  <!-- If database loading was enabled, start mongodb as well -->
  <include file="$(find arm_moveit_config)/launch/default_warehouse_db.launch" if="$(arg db)">
    <arg name="moveit_warehouse_database_path" value="$(arg db_path)"/>
  </include>

</launch>

Originally posted by matthewmarkey on ROS Answers with karma: 68 on 2020-05-08

Post score: 0


Original comments

Comment by gvdhoorn on 2020-05-08:
I haven't checked your complete URDF, but it's very likely the changes the MSA did to make it "Gazebo compatible" are not complete/entirely correct.

I would suggest to post an issue about this on the MoveIt issue tracker as it should work.

Comment by matthewmarkey on 2020-05-08:
Thank you sir I will do that.

Comment by matthewmarkey on 2020-05-08:
I just wanted to add that I was building the Moveit! package from the arm.xacro file itself. I have a feeling that this may be what is causing some issues with gazebo. I actually used the function in the MSA to create a new "gazebo ready" URDF file for the original arm.xacro file and saved it to my URDF directory. I then used that URDF instead of the .xacro to build a new Moveit! package...

The MSA would make a demo_gazebo.launch with this line:

<!-- By default, use the urdf location provided from the package -->
  <arg name="urdf_path" default="$(find version1_desc)/urdf/arm1.urdf"/>

instead of this one

 <!-- By default, use the urdf location provided from the package -->
      <arg name="urdf_path" default="$(find version1_desc)/urdf/arm.xacro"/>

I was able to get the model to spawn into gazebo.

Is this an appropriate way of doing this or have I done something incorrect and somehow gotten to the correct conclusion only to fail miserably later

Comment by gvdhoorn on 2020-05-08:
If I understand you correctly, the URDF is the one the MSA makes for you. It includes a nr of changes which are needed for Gazebo.

If your .xacro already contains those changes, then it would work of course.

Comment by matthewmarkey on 2020-05-08:
Ok thank you again for the prompt reply.

Comment by fvd on 2020-05-13:
Since you posted a follow-up question it seems like this problem is solved. Please summarize the solution and post it as an answer so others can benefit from it.

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

My urdf was not in the correct form. Modifying my previous work with correct tags ended up being the solution.

I was initially missing my tags as well as any associated tags (which I ended up needing to add later when my model was falling down due to gravity).

The URDF can be seen below as an example of what worked for me:

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from arm.xacro                      | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!--Joints-->
  <!--Cylinder-->
  <!--Rectangular  Prism-->
  <!--Cylinder Mesh-->
  <!--Box Mesh-->
  <!-- ros_control plugin -->

  <!-- base_link -->
  <gazebo reference="base_link">
  </gazebo>
  <!-- plat_link -->
  <gazebo reference="plat_link">
    <dampingFactor>1</dampingFactor>
  </gazebo>
  <!-- lock_link -->
  <gazebo reference="lock_link">
    <dampingFactor>1</dampingFactor>
  </gazebo>
  <!-- shoulder_link -->
  <gazebo reference="shoulder_link">
    <dampingFactor>1</dampingFactor>
  </gazebo>
  <!-- forearm_link -->
  <gazebo reference="forearm_link">
    <dampingFactor>1</dampingFactor>
  </gazebo>
  <!-- wrist_link -->
  <gazebo reference="wrist_link">
    <dampingFactor>1</dampingFactor>
  </gazebo>
  <create/>
  <gazebo>
    <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
      <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
      <legacyModeNS>true</legacyModeNS>
    </plugin>
  </gazebo>


  <link name="dummy_link"/>
  <!-- Dummy End Effector -->
  <joint name="dummy_joint" type="fixed">
    <parent link="dummy_link"/>
    <child link="base_link"/>
  </joint>
  <!--Base Link-->
  <link name="base_link">
    <inertial>
      <mass value="1.0"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.00153508333333" ixy="0" ixz="0" iyy="0.00153508333333" iyz="0" izz="0.00245"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder length="0.061" radius="0.07"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/base_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!--Plat Joint-->
  <joint name="plat_joint" type="revolute">
    <parent link="base_link"/>
    <child link="plat_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.0305"/>
    <limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
    <axis xyz="0 0 1"/>
  </joint>
  <transmission name="trans_plat">
    <type> transmission_interface/SimpleTransmission</type>
    <joint name="plat_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_plat">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <!--Plat Link-->
  <link name="plat_link">
    <inertial>
      <mass value="0.072"/>
      <origin rpy="0 0 0" xyz="0 0 0.004"/>
      <inertia ixx="6.5184e-05" ixy="0" ixz="0" iyy="6.5184e-05" iyz="0" izz="0.0001296"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.004"/>
      <geometry>
        <cylinder length="0.008" radius="0.06"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.004"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/plat_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!--Lock Joint-->
  <joint name="lock_joint" type="fixed">
    <parent link="plat_link"/>
    <child link="lock_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.004"/>
    <limit effort="0.1" lower="-1.5" upper="1.5" velocity="0.5"/>
    <axis xyz="0 0 1"/>
  </joint>
  <!--Lock Link-->
  <link name="lock_link">
    <inertial>
      <mass value="0.001"/>
      <origin rpy="0 0 0" xyz="0 0 0.0185"/>
      <inertia ixx="1.47416666667e-07" ixy="0" ixz="0" iyy="3.66166666667e-07" iyz="0" izz="2.85416666667e-07"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.0185"/>
      <geometry>
        <box size="0.02 0.055 0.037"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.0185"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/lock_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!--Shoulder Joint-->
  <joint name="shoulder_joint" type="revolute">
    <parent link="lock_link"/>
    <child link="shoulder_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.0265"/>
    <limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
    <axis xyz="0 1 0"/>
  </joint>
  <transmission name="trans_shoulder">
    <type> transmission_interface/SimpleTransmission</type>
    <joint name="shoulder_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_shoulder">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <!--Shoulder Link-->
  <link name="shoulder_link">
    <inertial>
      <mass value="0.163"/>
      <origin rpy="0 0 0" xyz="0 0 0.098"/>
      <inertia ixx="0.000639177333333" ixy="0" ixz="0" iyy="0.000700302333333" iyz="0" izz="7.19916666667e-05"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.098"/>
      <geometry>
        <box size="0.02 0.07 0.216"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.098"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/shoulder_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!--Forearm Joint-->
  <joint name="forearm_joint" type="revolute">
    <parent link="shoulder_link"/>
    <child link="forearm_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.191"/>
    <limit effort="10" lower="-1.5" upper="1.5" velocity="0.5"/>
    <axis xyz="0 1 0"/>
  </joint>
  <transmission name="trans_forearm">
    <type> transmission_interface/SimpleTransmission</type>
    <joint name="forearm_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_forearm">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <!--Forearm Link-->
  <link name="forearm_link">
    <inertial>
      <mass value="0.217"/>
      <origin rpy="0 0 0" xyz="0 0 0.055"/>
      <inertia ixx="0.00042315" ixy="0" ixz="0" iyy="0.000471975" iyz="0" izz="8.1375e-05"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.055"/>
      <geometry>
        <box size="0.03 0.06 0.150"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.055"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/forearm_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!--Wrist Joint-->
  <joint name="wrist_joint" type="revolute">
    <parent link="forearm_link"/>
    <child link="wrist_link"/>
    <origin rpy="0 0 0" xyz="0 0 0.110"/>
    <limit effort="1000" lower="-2.5" upper="2.5" velocity="0.5"/>
    <axis xyz="0 1 0"/>
  </joint>
  <transmission name="trans_wrist">
    <type> transmission_interface/SimpleTransmission</type>
    <joint name="wrist_joint">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_wrist">
      <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>
  <!--Wrist Link-->
  <link name="wrist_link">
    <inertial>
      <mass value="0.057"/>
      <origin rpy="0 0 0" xyz="0 0 0.045"/>
      <inertia ixx="7.03e-05" ixy="0" ixz="0" iyy="9.1675e-05" iyz="0" izz="2.5175e-05"/>
    </inertial>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.045"/>
      <geometry>
        <box size="0.02 0.07 0.120"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.045"/>
      <geometry>
        <mesh filename="package://version1_desc/meshes/wrist_link.dae" scale="1 1 1"/>
      </geometry>
      <material name="light_black"/>
    </visual>
  </link>
  <!-- Dummy End Effector -->
  <link name="dummy_eef"/>
  <!-- Dummy End Effector -->
  <joint name="eef_joint" type="fixed">
    <parent link="wrist_link"/>
    <child link="dummy_eef"/>
  </joint>
</robot>

Originally posted by matthewmarkey with karma: 68 on 2020-05-13

This answer was ACCEPTED on the original site

Post score: 0

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.