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

Using gazebo_ros_control with SDF instead of URDF

asked 2015-12-28 16:50:48 -0500

l0g1x gravatar image

My robot has a closed loop linkage, and therefore I cant use a URDF file as URDF only supports tree strucutres. Since SDF supports graph structures, I need to use that in order to simulate my robot. With that being said, I have a 2 actuators as well as a servo that I need to control. Normally, if I was to use an URDF, I would setup the tags in the URDF and then just include the gazebo_ros_control plugin in the URDF. But since the SDF specifications (sdformat.org) do not support tags, im not sure how to get the gazebo ros control plugin to work with my SDF file.

All the ros_control tutorials are based upon URDF, although there are lines in the tutorials stating "for your URDF/SDF file".

Currently, im simply adding this tag to the bottom of my SDF file (i wont include the whole thing for space reasons, for now at least):

....
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/surus_sim</robotNamespace>
        <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    </plugin>

</model>
</sdf>

And when i launch the simulation, this is the error I receive in which i cant pinpoint where it comes from (searched through the ros_control plugin code):

[INFO] [WallTime: 1451341627.255617] [0.000000] Loading model xml from ros parameter
[INFO] [WallTime: 1451341627.264068] [0.000000] Waiting for service /gazebo/spawn_sdf_model
[INFO] [WallTime: 1451341628.176358] [0.000000] Calling service /gazebo/spawn_sdf_model
[INFO] [WallTime: 1451341629.094573] [0.001000] Spawn status: SpawnModel: Successfully spawned model
[spawn_model-3] process has finished cleanly
log file: /home/krystian/.ros/log/1fbfd810-adb2-11e5-9876-001c4239cab7/spawn_model-3*.log
[ INFO] [1451341632.830481140, 0.001000000]: Loading gazebo_ros_control plugin
[ INFO] [1451341632.830768827, 0.001000000]: Starting gazebo_ros_control plugin in namespace: /surus_sim
[ INFO] [1451341632.832180175, 0.001000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[ERROR] [1451341633.054706078, 0.001000000]: Could not find the 'robot' element in the xml file
[ INFO] [1451341633.104100859, 0.001000000]: Loaded gazebo_ros_control.
[ INFO] [1451341633.150833544, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1451341633.232730090, 0.053000000]: Physics dynamic reconfigure ready.

The error [ERROR] [1451341633.054706078, 0.001000000]: Could not find the 'robot' element in the xml file is what I cannot figure out as only a URDF file contains the <robot> tag and SDF file does not. surus_sim is the name of the model in the sdf as well.

Any help would be appreciated. Would anyone know if the gazebo_ros_control plugin is meant to work directly with a SDF file? Ive looked around and a few people asked the question a while back but received no responses.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
5

answered 2016-01-26 23:49:28 -0500

l0g1x gravatar image

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.

edit flag offensive delete link more

Comments

Hi Krystian, Did you try to create a custom plugin?

Adnen gravatar image Adnen  ( 2016-04-04 08:30:07 -0500 )edit

@Adnen , I didnt create any custom plugin for this as I currently dont see any easy way of implementing a fix for this by creating a plugin. Did you have anything in mind?

l0g1x gravatar image l0g1x  ( 2016-04-13 21:27:12 -0500 )edit
1

@Krystian, I'm still a newbie in ROS and Gazebo, so when I tried your solution I couldn't spawn the model using two files. I followed the Gazebo tutorial and I created a model plugin. Now I can control the velocities of the joints via ROS Topics.

Adnen gravatar image Adnen  ( 2016-04-18 04:30:19 -0500 )edit

Have you played at all with getting this to be viewable inside gzweb? I was passed a ros based launch file to view a ros-controlled vehicle in gazebo. It works fine in gzclient, but I can't seem to figure out how to get the models to show up in gzweb...

srees304 gravatar image srees304  ( 2016-10-28 14:32:19 -0500 )edit

@Adnen Could you elaborate a bit more on how you created a model plugin to control velocities? Do you implement your own PID controller within the plugin or something like that? I am trying to control joints defined in an sdf using a pid controller receiveing commands from ros.

nathan_u gravatar image nathan_u  ( 2016-12-01 00:07:22 -0500 )edit

Hey ,@Krystian, may you introduce your method to convert sdf to urdf, I have trouble launching model in Gazebo.

rosroll gravatar image rosroll  ( 2017-08-07 01:46:57 -0500 )edit

you can refer: https://github.com/wojiaojiao/pegasus...

it to solve the issue that URDF not support Closed loop chains.

Angel-J gravatar image Angel-J  ( 2019-11-01 04:47:57 -0500 )edit

Interesting workaround. I have 2 joints. For first I am trying to load controller of type velocity_controllers/JointVelocityController and second one is of type velocity_controller/JointPositionController. But only first one is loaded correctly and can be controlled. Second does not load correctly and gives error: Failed to initialize the controller. Did you encounter this error by any chance?

AidenPierce gravatar image AidenPierce  ( 2022-05-03 07:15:37 -0500 )edit
0

answered 2019-11-01 04:48:02 -0500

Angel-J gravatar image

updated 2019-11-01 04:49:35 -0500

you can refer:
https://github.com/wojiaojiao/pegasus...

it to solve the issue that URDF not support Closed loop chains.

edit flag offensive delete link more

Question Tools

5 followers

Stats

Asked: 2015-12-28 16:50:48 -0500

Seen: 7,927 times

Last updated: Nov 01 '19