[ROS Q&A] 070 – Moving Joints in Gazebo Simple Example

Written by Ricardo Tellez

30/11/2017

Today’s ROS Question:

Moving Joints in Gazebo simple example? (https://answers.ros.org/question/273947/moving-joints-in-gazebo-simple-example/)

Answers:

You have to create the URDF, add the ros control plugin, and include a config file to configure the plugin. Let’s see how to do it step-by-step:

 

Step 0. Create a project in ROS Development Studio(ROSDS)

ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here. Please create a ROSject then open it.

Step 1. Create a URDF model

At first, let’s create a package for our code.

cd ~/catkin_ws/src
catkin_create_pkg simple_example_description ropy
cd simple_example_dexcription
mkdir launch
mkdir config
mkdir urdf

Then we create a URDF description called robot.urdf under the urdf folder with the following content

<?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>`

This description creates a 2 links robot.

For each link, there are 3 parts: inertia define the physical property of the link, the collision part define the behavior while collision occurs, and the visual part define the visualization of the link in the simulation.

Since we also want to control the robot, we have to include the gazebo plugin and define the type of the transmission.

Then we also need a config.yaml file under the config folder for the parameter of the controller with the following content.

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

base_to_second_joint_position_controller:
    type: effor_controllers/JointPositionController
    joint: base_to_second_joint
    pid: {p: 1.0, i: 1.0, d: 0.0}

The last step is to create a launch file to launch everything. We’ll call it spawn_robot.launch and put it under the launch folder.

<launch>
    <param name="robot_decription" textfile="$(find simple_example_description)/urdf/robot.urdf" />

    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model simple_model -param robot_description -y -6"/>
    <!-- load the controllers -->
    <rosparam file="$(find simple_example_description)/config/config.yaml" command="load"/>
    <node name="controller_spawner" pkg ="controller_manager" type="spawner" ns="/simple_model" args="base_to_second_joint_position_controller joint_state_controller --shutdown-timeout 3"/>
    <!-- converts joint states to TF transforms -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen">
        <remap from="joint_state" to="/simple_model/joint_states" />
    </node>
</launch>

Let’s start an empty simulation from Simulations->Empty then launch the launch file with

roslaunch simple_example_description spawn_robot.launch

You should see the robot is spawned in the center of the simulation world.

You can try to control the robot by publishing to the topic

rostopic pub -1 /simple_model/base_to_second_joint_position_controller/command std_msgs/Float64 "date: 3"

The robot is moving now!

 

Related resources:

 

Edit by: Tony Huang

Topics:
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

8 Comments

  1. Henrique

    Nice answer, but code has bugs (typo), especially the launch file. Code in the video and description are not the same.

    Reply
    • ROS Devel

      Hi Henrique,
      Could you please point out the typos as I am having trouble running this tutorial?

      Reply
      • Anonymous

        First typo:
        wrong:
        catkin_create_pkg simple_example_description ropy

        correct:
        catkin_create_pkg simple_example_description rospy

        Reply
  2. Yeoh

    Nice sharing for the explanation! Thanks a lot!
    From this video, I am more curious about how the controller work, like as you had mentioned that in the config.yaml, I also wanted to implemented on something like input the position for the joint which can generate the effort for the joint to init the robot motion. Your answer would be much appreciated!!!

    Reply
  3. Kashish Dhal

    Yes, definately there are some typos. I found step1 line 2 “ropy” instead of “rospy”, line3 “dexcription” instead of “description”. In the launch file, line10 “/joint_state” instead of “/joint_states”. But still after fixing these parameters, it doesn’t work, giving me an error, load_parameters: unable to set parameters cannot marshal None unless allow_none is enabled.
    I guess something else is missing, somebody able to figure out yet?

    Reply
    • Kashish Dhal

      By the way, these are the parameters set while running the roslaunch file:

      PARAMETERS
      * /base_to_second_joint_position_controller/joint: base_to_second_joint
      * /base_to_second_joint_position_controller/pid/d: 0.0
      * /base_to_second_joint_position_controller/pid/i: 1.0
      * /base_to_second_joint_position_controller/pid/p: 1.0
      * /base_to_second_joint_position_controller/type: effor_controllers…
      * /joint_state_controller/publish_rate: 20
      * /joint_state_controller/type: joint_state_contr…
      * /robot_decription: <?xml version="1….
      * /rosdistro: melodic
      * /rosversion: 1.14.3
      * /simple_model: None

      Reply

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This