diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index ad01d53925..e07423602f 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -166,10 +166,10 @@ This is how the model will look:
```xml
- j1
- 1.0
+ filename="gz-sim-joint-controller-system"
+ name="gz::sim::systems::JointController">
+ j1
+ 1.0
```
@@ -203,12 +203,13 @@ Replace the velocity mode plugin mentioned above with the following lines in the
```xml
- j1
- true
- 0.2
- 0.01
+ filename="gz-sim-joint-controller-system"
+ name="gz::sim::systems::JointController">
+ j1
+ true
+ 0.2
+ 0.01
+ topic_name
```
@@ -309,17 +310,17 @@ For this let's use the previously discussed SDF file.
```xml
- j1
- topic_name
- 1
- 0.1
- 0.01
- 1
- -1
- 1000
- -1000
+ filename="gz-sim-joint-position-controller-system"
+ name="gz::sim::systems::JointPositionController">
+ j1
+ topic_name
+ 1
+ 0.1
+ 0.01
+ 1
+ -1
+ 1000
+ -1000
```
@@ -591,28 +592,28 @@ This is how the model will look:
Append the following lines before `` tag in the SDF file.
```xml
-
- RR_position_control_joint1
- 0.7854
- 20
- 0.4
- 1.0
- -1
- 1
- -20
- 20
-
- RR_position_control_joint2
- -1.5708
- 10
- 0.2
- 0.5
- -1
- 1
- -10
- 10
+
+ RR_position_control_joint1
+ 0.7854
+ 20
+ 0.4
+ 1.0
+ -1
+ 1
+ -20
+ 20
+ topic_name
+ RR_position_control_joint2
+ -1.5708
+ 10
+ 0.2
+ 0.5
+ -1
+ 1
+ -10
+ 10
```
@@ -667,7 +668,7 @@ In case, PID gains are not specified then by default force mode will work.
4) Checking the progress of the commanded trajectory.
```bash
-gz topic -e -t "/model/RR_position_control/joint_trajectory_progress"
+gz topic -e -t "/topic_name_progress"
```
This returns the progress of the commanded trajectory which is a value between (0,1].