ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Could not find resource '[]' in 'hardware_interface::EffortJointInterface'.

asked 2018-03-20 06:44:31 -0500

dpakshimpo gravatar image

updated 2021-10-26 09:28:43 -0500

lucasw gravatar image

Hello,

The answers at questions: 1, 2 etc, does not seem to be solving this. I am having trouble setting up basic controllers in Gazebo. Can you please help me out with this please? When I launch the launch file, I get an error saying Could not find resource 'gripper_joint' in 'hardware_interface::EffortJointInterface'.

I confirmed that my controller_manager and spawner are in same name space:

$ rosservice list | grep controller_manager
/braccio/controller_manager/list_controller_types
/braccio/controller_manager/list_controllers
...

$ rosservice list | grep spawner
/braccio/controller_spawner/get_loggers
/braccio/controller_spawner/set_logger_level

My launch file:

<launch>

<!-- Convert an xacro and put on parameter server -->
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find braccio_arduino_ros_rviz)/urdf/braccio_arm.xacro" />

  <!-- these are the arguments you can pass this launch file, for example paused:=true -->
  <arg name="paused" default="false"/>
  <arg name="use_sim_time" default="true"/>
  <arg name="gui" default="true"/>
  <arg name="headless" default="false"/>
  <arg name="debug" default="false"/>

  <!-- We resume the logic in empty_world.launch -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">

   <arg name="world_name" default="$(find braccio_gazebo)/worlds/pick_place_multi.world"/>  

    <arg name="debug" value="$(arg debug)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="paused" value="$(arg paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="headless" value="$(arg headless)"/>
  </include>

<!-- Spawn a robot into Gazebo -->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -x 1.3 -y -0.3 -z 0.8 -model braccio" />

  <!-- Load joint controller configurations from YAML file to parameter server -->
  <rosparam file="$(find braccio_gazebo)/config/braccio_gazebo_joint_position.yaml" command="load"/>

  <!-- load the controllers -->
  <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
    output="screen" ns="/braccio" args="base_joint_pos_cntrl
                          shoulder_joint_pos_cntrl
                              elbow_joint_pos_cntrl
                              wrist_pitch_joint_pos_cntrl
                          wrist_roll_joint_pos_cntrl
                          sub_gripper_joint_pos_cntrl   
                              gripper_joint_pos_cntrl "/>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
</launch>

My YAML file:

braccio:
  # Publish all joint states -----------------------------------
  joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 50

  # Position Controllers ---------------------------------------
  base_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: base_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  shoulder_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: shoulder_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  elbow_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: elbow_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  wrist_pitch_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: wrist_pitch_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  wrist_roll_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: wrist_roll_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  gripper_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: gripper_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}
  sub_gripper_joint_pos_cntrl:
    type: effort_controllers/JointPositionController
    joint: sub_gripper_joint
    pid: {p: 100.0, i: 10.0, d: 1.0}

XACRO file for my robot using the Braccio Arduino arm:

<?xml version="1.0" ?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" 
    xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
    name="braccio">

  <xacro:property name="damping_value" value="203.35"/>
  <xacro:property name="friction_value" value="20.135"/>

<xacro:property name="kinect_box_length" value="0.3556" />
<xacro:property name="kinect_box_width" value="0.1778" />
<xacro:property name="kinect_box_height" value="0.0762" />
<xacro:property name="kinect_box_mass ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2018-03-21 00:12:06 -0500

dpakshimpo gravatar image

I managed to solve it. It turned out to be a stupid copy-paste mistake. In my XACRO file, I had the following interface,

<xacro:macro name="transmission_block" params="joint_name idx">
      <transmission name="tran_${idx}">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${joint_name}">
          <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
        </joint>
        <actuator name="motor__${idx}">
          <hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
          <mechanicalReduction>1</mechanicalReduction>
        </actuator>
      </transmission>
</xacro:macro>

In reality it should be an EffortJointInterface, instead of a PositionJointInterface

<xacro:macro name="transmission_block" params="joint_name idx">
      <transmission name="tran_${idx}">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${joint_name}">
          <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        </joint>
        <actuator name="motor__${idx}">
          <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
          <mechanicalReduction>1</mechanicalReduction>
        </actuator>
      </transmission>
</xacro:macro>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-03-20 06:44:31 -0500

Seen: 6,840 times

Last updated: Mar 21 '18