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

Moving Joints in Gazebo simple example?

asked 2017-10-24 08:59:47 -0500

Baumboon gravatar image

updated 2017-10-25 04:41:49 -0500

Hello Guys,

i have created my own arm model in gazebo with models from blender. I combine all meshes with joints to have a arm. Now i have no idea how i could move the joints.

I have a SDF model with 4 joints. Now i tried Ros Control but in the tut it was written it is for URDF models. Can i use it for SDF models too? Is there another option when i can´t use ros control?

Or would it be easier to use Ros with Move it for such an task ?

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
16

answered 2017-11-29 01:49:18 -0500

R. Tellez gravatar image

Hi, first, in order to move your robot joints you can use Gazebo or ROS. I recommend to use ROS because it is very well integrated, several controllers already provided, and it is a lot easier. However, if you want to learn how to do it with Gazebo itself, have a look at this git.

If you want to control the robot with ROS, then you need to do first a translation of your model to URDF. Sorry SDF does not work with ROS, specially if you want to show the robot in Rviz. So, go for the translation of format. To do a translation from SDF to URDF watch this video.

So now I will assume that you have a robot model in URDF which includes some joints. In order to keep the discussion sound I have created a simple URDF for a two joints robot. That is the URDF.

<?xml version="1.0"?>
<robot name="simple_example">
  <link name="base_link">
    <inertial>
        <mass value="10" />
        <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>
    <collision>
      <geometry>
        <cylinder radius="0.05" length="0.24" />
      </geometry>
        </collision>
    <visual>
      <geometry>
        <cylinder radius="0.05" length="0.24" />
      </geometry>
    </visual>
  </link>

  <link name="second_link">
    <inertial>
        <mass value="0.18" />
        <inertia ixx="0.0002835" ixy="0.0" ixz="0.0" iyy="0.0002835" iyz="0.0" izz="0.000324" />
    </inertial>
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0" />
    <collision>
      <geometry>
        <box size="0.05 0.05 0.15" />
      </geometry>
    </collision>
    <visual>
      <geometry>
        <box size="0.05 0.05 0.15" />
      </geometry>
    </visual>
  </link>

  <joint name="base_to_second_joint" type="continuous">
    <parent link="base_link"/>
    <child link="second_link"/>
    <axis xyz="1 0 0"/>
    <origin xyz="0.0 0.0 0.2" rpy="0.0 0.0 0.0"/> 
  </joint>

  <!--                GAZEBO RELATED PART                             -->

  <!-- ROS Control plugin for Gazebo -->
  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>/simple_model</robotNamespace>
    </plugin>
  </gazebo>

  <!-- transmission -->
  <transmission name="base_to_second_trans">
    <type>transmission_interface/SimpleTransmission</type>
    <actuator name="motor1">
      <mechanicalReduction>1</mechanicalReduction>
    </actuator>
    <joint name="base_to_second_joint">
      <hardwareInterface>EffortJointInterface</hardwareInterface>
    </joint>
  </transmission>
</robot>`

Now that URDF has the key elements you must use in any kinematic chain to be able to control it using ROS. Basically you do the following:

  1. Add a link for each movable element of the robot
  2. For each link add a joint which describes the union between the different links, which type of union is, and how one element moves in relation to the other.
  3. To be able to control with ROS you need to add the gazebo_ros_control plugin
  4. Finally, you have to include a transmission part, that is the one that actually indicates the controller to be used and for which joint.

Once you have all that, you need to create a config file that must be loaded at launch time, which contains the configuration of the controller itself. Here it is an example for the previous URDF.

simple_model:
joint_state_controller:
    type: joint_state_controller/JointStateController
    publish_rate: 20

base_to_second_joint_position_controller ...
(more)
edit flag offensive delete link more

Comments

Hello,

I have been following your answers and your video tutorials on YouTube. Would it be possible to do a video of spawing this robot model in Gazebo and controlling with MoveIt! It is wobbly and cannot find right damping and PID values.

dpakshimpo gravatar image dpakshimpo  ( 2018-03-22 00:08:48 -0500 )edit

One of the most clearly and very well described answers i ever got. Thank u very much.

Baumboon gravatar image Baumboon  ( 2018-03-26 11:09:00 -0500 )edit
1

On account of being a hardware dude, it took some time to touch up the code to make it work on my computer. I created this repository with working code: https://github.com/Toronto-Robotics-c...

BuilderMike gravatar image BuilderMike  ( 2020-02-12 12:31:23 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2017-10-24 08:59:47 -0500

Seen: 12,074 times

Last updated: Nov 29 '17