Skip to content

JointPositionController plugin

JointPositionController uses a PID controller to reach a desired joint position.

joint position control plugin
<plugin
 filename="gz-sim-joint-position-controller-system"
 name="gz::sim::systems::JointPositionController">
    <joint_name>j1</joint_name>
    <topic>topic_name</topic>
    <p_gain>1</p_gain>
    <i_gain>0.1</i_gain>
    <d_gain>0.01</d_gain>
    <i_max>1</i_max>
    <i_min>-1</i_min>
    <cmd_max>1000</cmd_max>
    <cmd_min>-1000</cmd_min>
</plugin>
cli command
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: -1.0"

Demo: Control joint position

robot sdf
<?xml version="1.0" ?>
<sdf version="1.8">
    <world name="default">
    <plugin
      filename="gz-sim-physics-system"
      name="gz::sim::systems::Physics">
    </plugin>
    <plugin
      filename="gz-sim-scene-broadcaster-system"
      name="gz::sim::systems::SceneBroadcaster">
    </plugin>

    <light type="directional" name="sun">
      <cast_shadows>true</cast_shadows>
      <pose>0 0 10 0 0 0</pose>
      <diffuse>1 1 1 1</diffuse>
      <specular>0.5 0.5 0.5 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.5 0.1 -0.9</direction>
    </light>

    <model name="ground_plane">
      <static>true</static>
      <link name="link">
        <collision name="collision">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
          </material>
        </visual>
      </link>
    </model>
  <model name='rrbot'>
    <pose>0 0 0 0 0 1.575</pose>
    <link name='link1'>
      <pose>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 1 0 -0 0</pose>
        <mass>1</mass>
        <inertia>
          <ixx>0.334167</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.334167</iyy>
          <iyz>0</iyz>
          <izz>0.00166667</izz>
        </inertia>
      </inertial>
      <collision name='link1_collision'>
        <pose>0 0 1 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.1 0.1 2</size>
          </box>
        </geometry>
      </collision>
      <visual name='link1_visual'>
        <pose>0 0 1 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.1 0.1 2</size>
          </box>
        </geometry>
        <material>
          <diffuse> 1 0.423529412 0.039215686 1</diffuse>
          <ambient> 1 0.423529412 0.039215686 1</ambient>
          <specular>1 0.423529412 0.039215686 1</specular>
        </material>
      </visual>
    </link>
    <joint name='joint1' type='revolute'>
      <pose relative_to='link1'>0 0.1 1.95 0 -0 0</pose>
      <parent>link1</parent>
      <child>link2</child>
      <axis>
        <xyz>0 1 0</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <damping>0.7</damping>
          <friction>0.0</friction>          
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='link2'>
      <pose relative_to='joint1'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0.45 0 -0 0</pose>
        <mass>1</mass>
        <inertia>
          <ixx>0.0841667</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0841667</iyy>
          <iyz>0</iyz>
          <izz>0.00166667</izz>
        </inertia>
      </inertial>
      <collision name='link2_collision'>
        <pose>0 0 0.45 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.1 0.1 1</size>
          </box>
        </geometry>
      </collision>
      <visual name='link2_visual'>
        <pose>0 0 0.45 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.1 0.1 1</size>
          </box>
        </geometry>
        <material>
          <diffuse> 0 0 0 1</diffuse>
          <ambient> 0 0 0 1</ambient>
          <specular>0 0 0 1</specular>
        </material>
      </visual>
    </link>

    <plugin
 filename="gz-sim-joint-position-controller-system"
 name="gz::sim::systems::JointPositionController">
 <joint_name>joint1</joint_name>
 <topic>joint_position</topic>
 <p_gain>40</p_gain>
 <i_gain>0.1</i_gain>
 <d_gain>5</d_gain>
 <i_max>1</i_max>
 <i_min>-1</i_min>
 <cmd_max>1000</cmd_max>
 <cmd_min>-1000</cmd_min>
</plugin>
  </model>
  <joint name='world_joint' type='fixed'>
    <parent>world</parent>
    <child>rrbot::link1</child>
    <pose>0 0 0 0 -0 0</pose>
  </joint>
  </world>
</sdf>

Don't forget joint damping section

1
2
3
4
5
6
<dynamics>
      <damping>0.7</damping>
      <friction>0.0</friction>          
      <spring_reference>0</spring_reference>
      <spring_stiffness>0</spring_stiffness>
    </dynamics>
send position command
gz topic -t "/joint2_position" -m gz.msgs.Double -p "data: -1.0"

alt text

how to tune

  • Set i_gain = 0 first
  • Increase p_gain until the joint reaches the target fast enough
  • Add d_gain to reduce overshoot and oscillation
  • Only then add a small i_gain if you still have steady-state error
  • Clamp the controller output with cmd_max/cmd_min and the integrator with i_max/i_min

Reference