Skip to content

Gazebo Joint Control

joint controllers from gazebo sim api reference tutorials

Gazebo provides three joint controller plugins which are JointController, JointPositionController, and JointTrajectoryController.

JointController

  • Velocity mode: This mode lets the user control the desired joint velocity directly.
  • Force mode: A user who wants to control joint velocity using a PID controller can use this mode.

All the parameters related to this controller can be found here.

Velocity mode

joint velocity with initial velocity and topic
1
2
3
4
5
6
7
<plugin
 filename="gz-sim-joint-controller-system"
 name="gz::sim::systems::JointController">
 <joint_name>j1</joint_name>
 <initial_velocity>1.0</initial_velocity>
 <topic>velocity_topic</topic>
</plugin>
control velocity speed
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"

Force mode

joint force mode
1
2
3
4
5
6
7
8
<plugin
 filename="gz-sim-joint-controller-system"
 name="gz::sim::systems::JointController">
 <joint_name>j1</joint_name>
 <use_force_commands>true</use_force_commands>
 <p_gain>0.2</p_gain>
 <i_gain>0.01</i_gain>
</plugin>

joint state

1
2
3
4
5
6
<plugin
    filename="gz-sim-joint-state-publisher-system"
    name="gz::sim::systems::JointStatePublisher">
    <joint_name>j1</joint_name>
    <topic>force_topic</topic>
</plugin>
echo joint state
gz topic -e -t /world/default/model/joint_controller_demo/joint_state

Demo

world demo
<?xml version="1.0"?>
<sdf version="1.6">
    <world name="default">
        <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="joint_controller_velocity">
            <pose>0 1 0 0 0 0</pose>
            <link name="base_link">
                <pose>0.0 0.0 0.0 0 0 0</pose>
                <inertial>
                    <inertia>
                        <ixx>2.501</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>2.501</iyy>
                        <iyz>0</iyz>
                        <izz>5</izz>
                    </inertia>
                    <mass>120.0</mass>
                </inertial>
                <visual name="base_visual">
                    <pose>0.0 0.0 0.0 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.5 0.5 0.01</size>
                        </box>
                    </geometry>
                </visual>
                <collision name="base_collision">
                    <pose>0.0 0.0 0.0 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.5 0.5 0.01</size>
                        </box>
                    </geometry>
                </collision>
            </link>
            <link name="rotor">
                <pose>0.0 0.0 0.1 0 0 0</pose>
                <inertial>
                    <inertia>
                        <ixx>0.032</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.032</iyy>
                        <iyz>0</iyz>
                        <izz>0.00012</izz>
                    </inertia>
                    <mass>0.6</mass>
                </inertial>
                <visual name="visual">
                    <geometry>
                        <box>
                            <size>0.25 0.1 0.05</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.2 0.8 0.2 1</ambient>
                        <diffuse>0.8 0 0 1</diffuse>
                    </material>
                </visual>
                <collision name="collision">
                    <geometry>
                        <box>
                            <size>0.25 0.1 0.05</size>
                        </box>
                    </geometry>
                </collision>
            </link>

            <joint name="world_fixed" type="fixed">
                <parent>world</parent>
                <child>base_link</child>
            </joint>

            <joint name="j1" type="revolute">
                <pose>0 0 -0.5 0 0 0</pose>
                <parent>base_link</parent>
                <child>rotor</child>
                <axis>
                    <xyz>0 0 1</xyz>
                </axis>
            </joint>

            <plugin
                filename="gz-sim-joint-controller-system"
                name="gz::sim::systems::JointController">
                <joint_name>j1</joint_name>
                <initial_velocity>1.0</initial_velocity>
                <topic>velocity_topic</topic>
            </plugin>
            <plugin
                filename="gz-sim-joint-state-publisher-system"
                name="gz::sim::systems::JointStatePublisher">
                <joint_name>j1</joint_name>
                <topic>velocity_j1_state</topic>
            </plugin>
        </model>

        <model name="joint_controller_force">
            <pose>0 0 0 0 0 0</pose>
            <link name="base_link">
                <pose>0.0 0.0 0.0 0 0 0</pose>
                <inertial>
                    <inertia>
                        <ixx>2.501</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>2.501</iyy>
                        <iyz>0</iyz>
                        <izz>5</izz>
                    </inertia>
                    <mass>120.0</mass>
                </inertial>
                <visual name="base_visual">
                    <pose>0.0 0.0 0.0 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.5 0.5 0.01</size>
                        </box>
                    </geometry>
                </visual>
                <collision name="base_collision">
                    <pose>0.0 0.0 0.0 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.5 0.5 0.01</size>
                        </box>
                    </geometry>
                </collision>
            </link>
            <link name="rotor">
                <pose>0.0 0.0 0.1 0 0 0</pose>
                <inertial>
                    <inertia>
                        <ixx>0.032</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.032</iyy>
                        <iyz>0</iyz>
                        <izz>0.00012</izz>
                    </inertia>
                    <mass>0.6</mass>
                </inertial>
                <visual name="visual">
                    <geometry>
                        <box>
                            <size>0.25 0.1 0.05</size>
                        </box>
                    </geometry>
                    <material>
                        <ambient>0.2 0.8 0.2 1</ambient>
                        <diffuse>0.8 0 0 1</diffuse>
                    </material>
                </visual>
                <collision name="collision">
                    <geometry>
                        <box>
                            <size>0.25 0.1 0.05</size>
                        </box>
                    </geometry>
                </collision>
            </link>

            <joint name="world_fixed" type="fixed">
                <parent>world</parent>
                <child>base_link</child>
            </joint>

            <joint name="j1" type="revolute">
                <pose>0 0 -0.5 0 0 0</pose>
                <parent>base_link</parent>
                <child>rotor</child>
                <axis>
                    <xyz>0 0 1</xyz>
                </axis>
            </joint>

            <plugin
                filename="gz-sim-joint-controller-system"
                name="gz::sim::systems::JointController">
                <joint_name>j1</joint_name>
                <use_force_commands>true</use_force_commands>
                <topic>force_topic</topic>
                <p_gain>0.2</p_gain>
                <i_gain>0.01</i_gain>
            </plugin>
            <plugin
                filename="gz-sim-joint-state-publisher-system"
                name="gz::sim::systems::JointStatePublisher">
                <joint_name>j1</joint_name>
                <topic>force_j1_state</topic>
            </plugin>
        </model>
    </world>
</sdf>
command and state topics
gz topic --list
#
/clock
/force_j1_state
/gazebo/resource_paths
/gui/camera/pose
/gui/currently_tracked
/gui/track
/stats
/velocity_j1_state
...
/force_topic
/velocity_topic
publish velocity to force controller
gz topic -t "/force_topic" -m gz.msgs.Double -p "data: 10.0"

alt text