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

Revision history [back]

So i did manage to figure out a work around to this, but its super hacked..

So basically to at least be able to use ros_control to control 2 actuators (cant view it in rviz since its a closed linkage) you need 2 robot_description parameters. ros_control loads from robot_description so you need to specify the path to your URDF file (if you only have a SDF, you can reference my answer here about converting from SDF to URDF). You need to specify the URDF file so that you can insert the <transmission> tags and associate which joints you want to use. If you convert URDF -> SDF or vis versa, you will still have all the same joint and link names, for example:

In my URDF file:

  <joint
    name="left_mid_actuator_joint"
    type="prismatic">
    <origin
      xyz="-0.5588 -0.010351 0"
      rpy="0 0 -3.9443E-31" />
    <parent
      link="left_top_actuator_link" />
    <child
      link="left_bot_actuator_link" />
    <axis
      xyz="-1 0 0" />
    <limit effort="100.0" lower="0" upper="1.4" velocity="0.2"/>
  </joint>

<transmission name="tran1">
  <type>transmission_interface/SimpleTransmission</type>
  <joint name="left_mid_actuator_joint">
    <hardwareInterface>EffortJointInterface</hardwareInterface>
  </joint>
  <actuator name="motor1">
    <hardwareInterface>EffortJointInterface</hardwareInterface>
    <mechanicalReduction>1</mechanicalReduction>
  </actuator>
</transmission>

and then you can see in my SDF file that i will have the same joint name left_mid_actuator_joint

<joint name='left_mid_actuator_joint' type='prismatic'>
  <child>left_bot_actuator_link</child>
  <parent>left_top_actuator_link</parent>
  <axis>
    <xyz>-0.685505 -4.48206e-15 -0.728068</xyz>
    <limit>
      <lower>0</lower>
      <upper>1.4</upper>
      <effort>100</effort>
      <velocity>0.2</velocity>
    </limit>
    <dynamics/>
  </axis>
</joint>

You then want to load both the SDF to spawn the model in gazebo (this actually eventually gets converted into URDF anyway) and the URDF so that ros_control can find the <transmission> tags. Make sure the URDF is loaded into robot_description and the SDF is loaded into some other parameter which you then pass as an arguement to spawn_model

<param name="robot_description" textfile="$(find rmc_simulation)/surus_sim/robots/surus_sim.URDF" />
<param name="robot_description_sdf" textfile="$(find rmc_simulation)/surus_sim/robots/surus_sim.sdf" />

<node
  name="spawn_model"
  pkg="gazebo_ros"
  type="spawn_model"
  args="-sdf -param robot_description_sdf -model surus_sim -x 0 -y 0.6 -z 0.3"
  output="screen">
</node>

<rosparam file="$(find rmc_simulation)/gazebo_config/control/surus_control.yaml" command="load"/>

<node name="controller_spawner" 
    pkg="controller_manager" 
    type="spawner" respawn="false" output="screen"
    args="joint1_position_controller joint2_position_controller joint_state_controller"/>

Where my yaml is:

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

  # Position Controllers ---------------------------------------
  joint1_position_controller:
    type: effort_controllers/JointPositionController
    joint: right_mid_actuator_joint
    pid: {p: 100.0, i: 0.01, d: 10.0}
  joint2_position_controller:
    type: effort_controllers/JointPositionController
    joint: left_mid_actuator_joint
    pid: {p: 100.0, i: 0.01, d: 10.0}

Like i said, this is NOT the proper way of doing this. If someone could still post an answer as to how to directly include ros_control into a sdf, that would be splendid.