From 007bdaf1c92c3a91a75d4c41b55aca19b83d9751 Mon Sep 17 00:00:00 2001
From: yaswanth
Date: Mon, 11 Dec 2023 11:58:03 +0500
Subject: [PATCH 01/29] Added joint controllers tutorial .md file
Signed-off-by: yaswanth
---
tutorials/joint_controller_tutorial.md | 0
1 file changed, 0 insertions(+), 0 deletions(-)
create mode 100644 tutorials/joint_controller_tutorial.md
diff --git a/tutorials/joint_controller_tutorial.md b/tutorials/joint_controller_tutorial.md
new file mode 100644
index 0000000000..e69de29bb2
From 4424f9e36e5f54e2bf646985cddefd6d770c38a8 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Mon, 11 Dec 2023 12:34:17 +0530
Subject: [PATCH 02/29] Rename joint_controller_tutorial.md to
joint_controller.md
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 1 +
tutorials/joint_controller_tutorial.md | 0
2 files changed, 1 insertion(+)
create mode 100644 tutorials/joint_controller.md
delete mode 100644 tutorials/joint_controller_tutorial.md
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
new file mode 100644
index 0000000000..d3f5a12faa
--- /dev/null
+++ b/tutorials/joint_controller.md
@@ -0,0 +1 @@
+
diff --git a/tutorials/joint_controller_tutorial.md b/tutorials/joint_controller_tutorial.md
deleted file mode 100644
index e69de29bb2..0000000000
From 8c9c2bf8bf48c0aa594df8da556904f4f7dac7ee Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Mon, 11 Dec 2023 12:58:19 +0530
Subject: [PATCH 03/29] added JointController and JointPositionController
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 322 ++++++++++++++++++++++++++++++++++
1 file changed, 322 insertions(+)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index d3f5a12faa..9fe6bc3f9d 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -1 +1,323 @@
+# Joint controllers in Gazebo
+
+# 1) JointController
+
+- Joint controller which can be attached to a model with a reference to a single joint.
+- Currently, only the first axis of a joint is actuated.
+
+possible use of this controller type is where one wants only to actuate a single joint.
+
+### modes of JointController
+
+1) Velocity mode
+
+2) Force mode
+
+### velocity mode:
+
+This mode lets the user control the desired joint directly.
+
+### force mode:
+
+A user who wants to control joint velocity using a PID controller can use this mode.
+
+This mode lets the user explicitly set the values of PID gains and also bounds for velocity.
+
+Note: This mode is for the user who looking to manually tune PID for velocity control according to a specific use case (e.g. Custom models). For general purposes, velocity mode will give the best results.
+
+Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/4.5/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
+
+In both the modes commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel`.
+
+Message data type: `Double`
+
+Example usage
+
+Let's see an example for both modes using a simple model having only one joint.
+
+For controlling joints one would require adding the Gazebo joint controller plugin to the existing .sdf file.
+
+1) Save the SDF file in the desired directory or create one
+
+e.g.
+
+```markdown
+mkdir gz_tutorial
+cd gz_turtorial
+```
+
+2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller example)
+
+after changing the directory, one can name their SDF file as `example.sdf`
+
+- SDF file:
+
+```xml
+
+
+
+
+
+
+
+
+
+ true
+ 0 0 10 0 0 0
+ 1 1 1 1
+ 0.5 0.5 0.5 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+ 0 0 0 0 0 0
+
+ 0.0 0.0 0.0 0 0 0
+
+
+ 2.501
+ 0
+ 0
+ 2.501
+ 0
+ 5
+
+ 120.0
+
+
+ 0.0 0.0 0.0 0 0 0
+
+
+ 0.5 0.5 0.01
+
+
+
+
+ 0.0 0.0 0.0 0 0 0
+
+
+ 0.5 0.5 0.01
+
+
+
+
+
+ 0.0 0.0 0.1 0 0 0
+
+
+ 0.032
+ 0
+ 0
+ 0.032
+ 0
+ 0.00012
+
+ 0.6
+
+
+
+
+ 0.25 0.1 0.05
+
+
+
+ 0.2 0.8 0.2 1
+
+
+
+
+
+ 0.25 0.1 0.05
+
+
+
+
+
+
+ world
+ base_link
+
+
+
+ 0 0 -0.5 0 0 0
+ base_link
+ rotor
+
+ 0 0 1
+
+
+
+
+
+```
+
+3) Run the following command to launch the gazebo simulation:
+
+```powershell
+gz sim example.sdf
+```
+
+This is how the model will look:
+
+
+
+
+4) Now let's add the gazebo joint controller plugin to the SDF file. Add the following line to your file just before the tag .
+
+- Velocity mode
+
+```xml
+
+ j1
+ 1.0
+
+```
+
+The initial velocity is set to 1.0 rad/s.
+
+result:
+
+
+
+
+
+
+
+one can change the joint velocity by publishing a msg on the topic
+
+"/model/joint_controller_demo/joint/j1/cmd_vel”
+
+Or can change the topic name within the plugin
+
+before add following line
+
+```xml
+topic_name
+```
+
+e.g.
+
+```xml
+gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
+```
+
+
+
+
+
+- Force model
+
+same as velocity mode change add the following line to the SDF file
+
+```xml
+
+ joint_thename
+ true
+ 0.2
+ 0.01
+
+```
+
+This would look almost the same as velocity mode if PID gains are tuned properly.
+
+Here the state of the joint is obtained using the Gazebo’s JointStatepublisher plugin. Please visit [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointStatePublisher.html#:~:text=JointStatePublisher%20Class%20Reference) for more information.
+
+
+
+
+
+
+An example where p_gain was set to 2 and the joint controller failed to reach the desired velocity and behaved absurdly due to improper gains.
+
+
+
+
+## 2) JointPositionController
+
+- Joint position controller which can be attached to a model with a reference to a single joint.
+- One can mention the axis of the joint they want to control.
+
+JointPositionController uses a PID controller to reach a desired joint.
+
+All the parameters related to this controller can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointPositionController.html#:~:text=the%20target%20position.-,System%20Parameters,-%3Cjoint_name%3E%20The).
+
+Commanded position(cmd_pos) can be published or subscribed at the topic: `/model//joint///cmd_pos` by default.
+
+Message data type: `Double`.
+
+Example usage:
+
+For this let's use this previously discussed SDF file.
+
+1) adding the JointPositionController plugin to SDF.
+
+```xml
+
+ j1
+ topic_name
+ 1
+ 0.1
+ 0.01
+ 1
+ -1
+ 1000
+ -1000
+
+```
+
+2) Sending joint position command
+
+```xml
+gz topic -t "/topic_name" -m gz.msgs.Double -p "data: -1.0"
+```
+
+
+
+## 3) JointTrajectoryController.
+
+- Joint trajectory controller, which can be attached to a model with reference to one or more 1-axis joints to follow a trajectory.
+
+JointTrajectoryController lets’s user specify the required position, velocity, and effort. For velocity and position, this controller uses a PID controller.
+
+A detailed description of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
+
+By default, the trajectory message can be published or subscribed at `/model/${MODEL_NAME}/joint_trajectory`
+
+Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classignition_1_1msgs_1_1JointTrajectory.html)
+
+All the parameters related to JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=the%20trajectory%20points.-,System%20Parameters,-%3Ctopic%3E%20The).
+
+Example usage:
+
+let’s set up a new model for this example. A two-linked pendulum has a total of two joints to control.
+
+```xml
+
+```
From e60d1b81a37efa9fac76368711d38e44e5f52c8b Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Mon, 11 Dec 2023 13:59:49 +0530
Subject: [PATCH 04/29] minor changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 5 ++---
1 file changed, 2 insertions(+), 3 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 9fe6bc3f9d..677e9c0479 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -306,13 +306,12 @@ gz topic -t -e
JointTrajectoryController lets’s user specify the required position, velocity, and effort. For velocity and position, this controller uses a PID controller.
-A detailed description of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
+A detailed description and related parameter of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
-By default, the trajectory message can be published or subscribed at `/model/${MODEL_NAME}/joint_trajectory`
+By default, the trajectory message can be published or subscribed at ```/model/${MODEL_NAME}/joint_trajectory``` by default
Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classignition_1_1msgs_1_1JointTrajectory.html)
-All the parameters related to JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=the%20trajectory%20points.-,System%20Parameters,-%3Ctopic%3E%20The).
Example usage:
From 0a4edcccd0d299149ae7423e799d14b38c4d0ce7 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Mon, 11 Dec 2023 14:08:41 +0530
Subject: [PATCH 05/29] formatting changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 36 +++++++++++++++--------------------
1 file changed, 15 insertions(+), 21 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 677e9c0479..10f80fe833 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -4,27 +4,25 @@
# 1) JointController
- Joint controller which can be attached to a model with a reference to a single joint.
-- Currently, only the first axis of a joint is actuated.
-
-possible use of this controller type is where one wants only to actuate a single joint.
-
+- Currently, only the first axis of a joint can be actuated.
+
### modes of JointController
1) Velocity mode
2) Force mode
-### velocity mode:
+### Velocity mode:
-This mode lets the user control the desired joint directly.
+This mode lets the user control the desired joint velocity directly.
-### force mode:
+### Force mode:
A user who wants to control joint velocity using a PID controller can use this mode.
-This mode lets the user explicitly set the values of PID gains and also bounds for velocity.
+This mode lalso ets the user explicitly set the values of PID gains and also bounds for velocity.
-Note: This mode is for the user who looking to manually tune PID for velocity control according to a specific use case (e.g. Custom models). For general purposes, velocity mode will give the best results.
+Note: This force mode is for the user who looking to manually tune PID for velocity control according to a specific use case (e.g. Custom models). For general purposes, velocity mode will give the best results.
Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/4.5/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
@@ -47,9 +45,9 @@ mkdir gz_tutorial
cd gz_turtorial
```
-2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller example)
+2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller [example](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_controller.sdf).
-after changing the directory, one can name their SDF file as `example.sdf`
+After changing the directory, one can name their SDF file as `example.sdf`
- SDF file:
@@ -172,7 +170,7 @@ This is how the model will look:
-4) Now let's add the gazebo joint controller plugin to the SDF file. Add the following line to your file just before the tag .
+4) Now let's add the gazebo joint controller plugin to the SDF file. Add the following line to your file just before the tag ``````.
- Velocity mode
@@ -195,19 +193,15 @@ result:
-one can change the joint velocity by publishing a msg on the topic
-
-"/model/joint_controller_demo/joint/j1/cmd_vel”
+One can change the joint velocity by publishing a msg on the topic ```/model/joint_controller_demo/joint/j1/cmd_vel``` or can change the topic name within the plugin
-Or can change the topic name within the plugin
-
-before add following line
+To change the topic name add following line before `````` tag in SDF file.
```xml
topic_name
```
-e.g.
+- Send velocity commands
```xml
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
@@ -217,9 +211,9 @@ gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
-- Force model
+- Force mode
-same as velocity mode change add the following line to the SDF file
+Same as velocity mode add the following line to the SDF file
```xml
Date: Tue, 12 Dec 2023 01:46:55 +0530
Subject: [PATCH 06/29] added gifs
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 7 ++++++-
1 file changed, 6 insertions(+), 1 deletion(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 10f80fe833..8e570112e2 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -240,12 +240,17 @@ An example where p_gain was set to 2 and the joint controller failed to reach th
+
+
+
+
+
## 2) JointPositionController
- Joint position controller which can be attached to a model with a reference to a single joint.
- One can mention the axis of the joint they want to control.
-JointPositionController uses a PID controller to reach a desired joint.
+JointPositionController uses a PID controller to reach a desired joint position.
All the parameters related to this controller can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointPositionController.html#:~:text=the%20target%20position.-,System%20Parameters,-%3Cjoint_name%3E%20The).
From e94bdc94b103922aa1177a6122ae3f3b76395472 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 02:28:24 +0530
Subject: [PATCH 07/29] Added JointTrajectoryController
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 305 +++++++++++++++++++++++++++++++++-
1 file changed, 304 insertions(+), 1 deletion(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 8e570112e2..8478c6234d 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -314,8 +314,311 @@ Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classig
Example usage:
-let’s set up a new model for this example. A two-linked pendulum has a total of two joints to control.
+let’s set up a new model for this example. A two-linked pendulum whihc has a total of two joints to control. Can name it as `example2.sdf`.
+
+- SDF file:
```xml
+
+
+
+
+
+
+
+
+
+
+ 0.4 0.4 0.4
+ false
+
+
+
+
+
+
+ false
+ 5 5 5 0 0 0
+ 0.8 0.8 0.8 1
+ 0.2 0.2 0.2 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -1 -1 -1
+
+
+
+
+
+
+ -0.1 0 0 0 1.5708 0
+ true
+
+
+
+
+ 0 0 1
+ 5 5
+
+
+
+ 0.5 0.5 0.5 1
+ 0.5 0.5 0.5 1
+
+
+
+
+
+
+ 0 0 0 0 -3.14159 0
+
+
+ world
+ RR_position_control_link0
+
+
+
+
+
+
+ 0.025
+
+
+
+
+
+
+ 0.025
+
+
+
+ 0 0.5 0.5 1
+ 0 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+ 0 0 0.1 0 0 0
+
+
+
+ 0.01
+ 0.2
+
+
+
+
+
+
+ 0.0125
+
+
+
+
+
+
+ 0.01
+ 0.2
+
+
+
+ 0.5 0 0 1
+ 0.8 0 0 1
+ 0.8 0 0 1
+
+
+
+ 0 0 0.2 0 0 0
+
+
+ 0.0125
+
+
+
+ 0.5 0.5 0.5 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+ 0.1
+
+ 0.0003358
+ 0.0003358
+ 0.000005
+
+
+
+
+ 0 0 0.1 0 0 0
+
+
+
+ 0.01
+ 0.2
+
+
+
+
+
+
+ 0.01
+ 0.2
+
+
+
+ 0.5 0 0 1
+ 0.8 0 0 1
+ 0.8 0 0 1
+
+
+
+ 0.1
+
+ 0.0003358
+ 0.0003358
+ 0.000005
+
+
+
+
+
+ 0 0 0 0 0 0
+ RR_position_control_link0
+ RR_position_control_link1
+
+ 1 0 0
+
+ 0.5
+
+
+
+
+ 0 0 0.1 0 0 0
+ RR_position_control_link1
+ RR_position_control_link2
+
+ 1 0 0
+
+ 0.25
+
+
+
+
+
+
+
+
+
```
+
+1) Launching gazebo sim
+
+```xml
+gz sim example2.sdf
+```
+
+This is how the model will look:
+
+
+
+Note: by default velocity and position control are disabled if one want to use these mode, one must specify the PID gains value according to usage.
+
+if PID gains are not specified then by default force mode will work.
+
+4) Checking progress of commanded trajectory
+
+```xml
+gz topic -e -t "/model/example2/joint_trajectory_progress"
+```
+
+This return the progress of commanded trajectory which is a value between (0,1].
+
+Finally JointTrajectoryController’s can used for hybrid control of manipulator robot were value from position PID, velocity PID and commanded force value are summed up and are applied.
From ad3dd9abf2b2c6a245528499ec856cad0f9338c8 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 02:55:26 +0530
Subject: [PATCH 08/29] final changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 48 +++++++++++++++++------------------
1 file changed, 24 insertions(+), 24 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 8478c6234d..b5b9fc96cf 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -1,5 +1,5 @@
-# Joint controllers in Gazebo
+\page jointcontrollers Joint Controllers
# 1) JointController
@@ -20,13 +20,13 @@ This mode lets the user control the desired joint velocity directly.
A user who wants to control joint velocity using a PID controller can use this mode.
-This mode lalso ets the user explicitly set the values of PID gains and also bounds for velocity.
+This mode let's the user explicitly set the values of PID gains and also bounds for velocity.
-Note: This force mode is for the user who looking to manually tune PID for velocity control according to a specific use case (e.g. Custom models). For general purposes, velocity mode will give the best results.
+Note: This force mode is for the user who looking to manually tune PID gains for velocity control according to a specific use case (e.g. Custom models). For general testing purposes, velocity mode will give the best results.
Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/4.5/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
-In both the modes commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel`.
+In both the modes commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel` by default.
Message data type: `Double`
@@ -34,7 +34,7 @@ Example usage
Let's see an example for both modes using a simple model having only one joint.
-For controlling joints one would require adding the Gazebo joint controller plugin to the existing .sdf file.
+For controlling joints one would require adding the Gazebo's joint controller plugin to the existing .sdf file.
1) Save the SDF file in the desired directory or create one
@@ -45,7 +45,7 @@ mkdir gz_tutorial
cd gz_turtorial
```
-2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller [example](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_controller.sdf).
+2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller [example](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_controller.sdf))
After changing the directory, one can name their SDF file as `example.sdf`
@@ -170,7 +170,7 @@ This is how the model will look:
-4) Now let's add the gazebo joint controller plugin to the SDF file. Add the following line to your file just before the tag ``````.
+4) Now let's add the gazebo JointController plugin to the SDF file. Add the following line to your file just before the tag ``````.
- Velocity mode
@@ -201,7 +201,7 @@ To change the topic name add following line before `````` tag in SDF fi
topic_name
```
-- Send velocity commands
+- Sending velocity commands
```xml
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
@@ -235,7 +235,7 @@ Here the state of the joint is obtained using the Gazebo’s JointStatepublisher
-An example where p_gain was set to 2 and the joint controller failed to reach the desired velocity and behaved absurdly due to improper gains.
+An example where p_gain was set to 2.0 and the joint controller failed to reach the desired velocity and behaved absurdly due to improper gains is shown below.
@@ -260,7 +260,7 @@ Message data type: `Double`.
Example usage:
-For this let's use this previously discussed SDF file.
+For this let's use the previously discussed SDF file.
1) adding the JointPositionController plugin to SDF.
@@ -280,7 +280,7 @@ For this let's use this previously discussed SDF file.
```
-2) Sending joint position command
+2) Sending joint position command.
```xml
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: -1.0"
@@ -289,10 +289,10 @@ gz topic -t "/topic_name" -m gz.msgs.Double -p "data: -1.0"
-3) Checking joint state
+3) Checking joint state.
```jsx
-gz topic -t -e
+gz topic -e -t /world/default/model/joint_controller_demo/joint_state
```
@@ -303,18 +303,18 @@ gz topic -t -e
- Joint trajectory controller, which can be attached to a model with reference to one or more 1-axis joints to follow a trajectory.
-JointTrajectoryController lets’s user specify the required position, velocity, and effort. For velocity and position, this controller uses a PID controller.
+JointTrajectoryController lets’s user specify the required position, velocity, and effort with respect to time. For velocity and position, this controller uses a PID controller.
A detailed description and related parameter of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
-By default, the trajectory message can be published or subscribed at ```/model/${MODEL_NAME}/joint_trajectory``` by default
+The trajectory message can be published or subscribed at ```/model/${MODEL_NAME}/joint_trajectory``` by default.
Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classignition_1_1msgs_1_1JointTrajectory.html)
Example usage:
-let’s set up a new model for this example. A two-linked pendulum whihc has a total of two joints to control. Can name it as `example2.sdf`.
+let’s set up a new model for this example. A two-linked pendulum which has a total of two joints to control ( [joint_trajectory_controller](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_trajectory_controller.sdf) is the original example). Can name it as `example2.sdf`.
- SDF file:
@@ -522,7 +522,7 @@ let’s set up a new model for this example. A two-linked pendulum whihc has a t
```
-1) Launching gazebo sim
+1) Launching gazebo simulation.
```xml
gz sim example2.sdf
@@ -534,9 +534,9 @@ This is how the model will look:
-2) Add JointTrajectoryController plugin and let’s do position control for both joints.
+2) Adding JointTrajectoryController plugin and let’s do position control for both joints.
-Append following lines before tag in SDF file.
+Append following lines before `````` tag in SDF file.
```xml
tag in SDF file.
```
-3) Sending trajectory message (Can also change the topic name)
+3) Sending trajectory message (Can also change the topic name).
```xml
gz topic -t "topic_name" -m gz.msgs.JointTrajectory -p '
@@ -609,11 +609,11 @@ gz topic -t "topic_name" -m gz.msgs.JointTrajectory -p '
-Note: by default velocity and position control are disabled if one want to use these mode, one must specify the PID gains value according to usage.
+Note: by default velocity and position control are disabled if one want to use these mode, they must specify the PID gains value according to usage.
-if PID gains are not specified then by default force mode will work.
+In case, PID gains are not specified then by default force mode will work.
-4) Checking progress of commanded trajectory
+4) Checking progress of commanded trajectory.
```xml
gz topic -e -t "/model/example2/joint_trajectory_progress"
@@ -621,4 +621,4 @@ gz topic -e -t "/model/example2/joint_trajectory_progress"
This return the progress of commanded trajectory which is a value between (0,1].
-Finally JointTrajectoryController’s can used for hybrid control of manipulator robot were value from position PID, velocity PID and commanded force value are summed up and are applied.
+Finally JointTrajectoryController can used for hybrid control (e.g In manipulator robots) were value from position PID, velocity PID and commanded force value are summed up and are applied.
From f34fe929739d1154a1bfe8349bbf9f4961f7d453 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 02:58:28 +0530
Subject: [PATCH 09/29] minor changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 1 +
1 file changed, 1 insertion(+)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index b5b9fc96cf..3b76d5b8f5 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -1,6 +1,7 @@
\page jointcontrollers Joint Controllers
+Gazebo provides basically three joint controller plugins. Let's see a detailed description of each of them and example usage to help users to select right joint controller for their usage.
# 1) JointController
- Joint controller which can be attached to a model with a reference to a single joint.
From ee108441a2821d787fc917a705d01abb4a7d7843 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 03:05:26 +0530
Subject: [PATCH 10/29] minor changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 11 +++++------
1 file changed, 5 insertions(+), 6 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 3b76d5b8f5..8d53f1d43c 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -7,7 +7,7 @@ Gazebo provides basically three joint controller plugins. Let's see a detailed d
- Joint controller which can be attached to a model with a reference to a single joint.
- Currently, only the first axis of a joint can be actuated.
-### modes of JointController
+### Modes of JointController
1) Velocity mode
@@ -186,7 +186,6 @@ This is how the model will look:
The initial velocity is set to 1.0 rad/s.
-result:
@@ -194,7 +193,7 @@ result:
-One can change the joint velocity by publishing a msg on the topic ```/model/joint_controller_demo/joint/j1/cmd_vel``` or can change the topic name within the plugin
+One can change the joint velocity by publishing a message on the topic ```/model/joint_controller_demo/joint/j1/cmd_vel``` or can change the topic name within the plugin
To change the topic name add following line before `````` tag in SDF file.
@@ -263,7 +262,7 @@ Example usage:
For this let's use the previously discussed SDF file.
-1) adding the JointPositionController plugin to SDF.
+1) Adding the JointPositionController plugin to SDF.
```xml
Date: Tue, 12 Dec 2023 11:47:29 +0530
Subject: [PATCH 11/29] removed trailing-whitespace
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 21 +++++++++------------
1 file changed, 9 insertions(+), 12 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 8d53f1d43c..108e38b16b 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -1,27 +1,26 @@
\page jointcontrollers Joint Controllers
-Gazebo provides basically three joint controller plugins. Let's see a detailed description of each of them and example usage to help users to select right joint controller for their usage.
+Gazebo provides three joint controller plugins. Let's see a detailed description of each of them and example usage to help users to select right joint controller for their usage.
# 1) JointController
- Joint controller which can be attached to a model with a reference to a single joint.
- Currently, only the first axis of a joint can be actuated.
-
+
### Modes of JointController
-1) Velocity mode
+1) Velocity mode.
-2) Force mode
+2) Force mode.
### 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.
-This mode let's the user explicitly set the values of PID gains and also bounds for velocity.
+This mode lets the user explicitly set the values of PID gains and also bounds for velocity.
Note: This force mode is for the user who looking to manually tune PID gains for velocity control according to a specific use case (e.g. Custom models). For general testing purposes, velocity mode will give the best results.
@@ -193,7 +192,7 @@ The initial velocity is set to 1.0 rad/s.
-One can change the joint velocity by publishing a message on the topic ```/model/joint_controller_demo/joint/j1/cmd_vel``` or can change the topic name within the plugin
+One can change the joint velocity by publishing a message on the topic ```/model/joint_controller_demo/joint/j1/cmd_vel``` or can change the topic name within the plugin.
To change the topic name add following line before `````` tag in SDF file.
@@ -213,7 +212,7 @@ gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
- Force mode
-Same as velocity mode add the following line to the SDF file
+Same as velocity mode add the following line to the SDF file.
```xml
```
-This would look almost the same as velocity mode if PID gains are tuned properly.
+This would look almost the same as velocity mode if PID gains are tuned properly.
Here the state of the joint is obtained using the Gazebo’s JointStatepublisher plugin. Please visit [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointStatePublisher.html#:~:text=JointStatePublisher%20Class%20Reference) for more information.
@@ -303,7 +302,7 @@ gz topic -e -t /world/default/model/joint_controller_demo/joint_state
- Joint trajectory controller, which can be attached to a model with reference to one or more 1-axis joints to follow a trajectory.
-JointTrajectoryController lets’s user specify the required position, velocity, and effort with respect to time. For velocity and position, this controller uses a PID controller.
+JointTrajectoryController lets’s user specify the required position, velocity, and effort with respect to time. For velocity and position, this controller uses a PID controller.
A detailed description and related parameter of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
@@ -515,9 +514,7 @@ let’s set up a new model for this example. A two-linked manipulator arm which
-
-
```
From f49869ccd0d46d753399bc6d92d93fd043b54210 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 22:26:38 +0530
Subject: [PATCH 12/29] corrected formatting
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 51 +++++++++++++++--------------------
1 file changed, 22 insertions(+), 29 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 108e38b16b..79a42cc828 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -1,4 +1,3 @@
-
\page jointcontrollers Joint Controllers
Gazebo provides three joint controller plugins. Let's see a detailed description of each of them and example usage to help users to select right joint controller for their usage.
@@ -22,9 +21,9 @@ A user who wants to control joint velocity using a PID controller can use this m
This mode lets the user explicitly set the values of PID gains and also bounds for velocity.
-Note: This force mode is for the user who looking to manually tune PID gains for velocity control according to a specific use case (e.g. Custom models). For general testing purposes, velocity mode will give the best results.
+**Note**: This force mode is for the user who looking to manually tune PID gains for velocity control according to a specific use case (e.g. Custom models). For general testing purposes, velocity mode will give the best results.
-Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/4.5/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
+Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
In both the modes commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel` by default.
@@ -34,20 +33,20 @@ Example usage
Let's see an example for both modes using a simple model having only one joint.
-For controlling joints one would require adding the Gazebo's joint controller plugin to the existing .sdf file.
+For controlling joints one would require adding the Gazebo's joint controller plugin to the existing `.sdf` file.
1) Save the SDF file in the desired directory or create one
e.g.
-```markdown
+```bash
mkdir gz_tutorial
cd gz_turtorial
```
-2) For this tutorial we will be using the following SDF file (this is just a slight modification of the original joint_controller [example](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_controller.sdf))
+2) In this tutorial we will be using the following SDF file (this is just a slight modification of the original `joint_controller.sdf` [example](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_controller.sdf))
-After changing the directory, one can name their SDF file as `example.sdf`
+After changing the directory, name the SDF file as `example.sdf`
- SDF file:
@@ -161,8 +160,8 @@ After changing the directory, one can name their SDF file as `example.sdf`
3) Run the following command to launch the gazebo simulation:
-```powershell
-gz sim example.sdf
+```bash
+gz sim -v 4 -r example.sdf
```
This is how the model will look:
@@ -170,7 +169,7 @@ This is how the model will look:
-4) Now let's add the gazebo JointController plugin to the SDF file. Add the following line to your file just before the tag ``````.
+4) Now let's add the Gazebo JointController plugin to the SDF file. Add the following line to your file just before the tag ``.
- Velocity mode
@@ -202,14 +201,13 @@ To change the topic name add following line before `````` tag in SDF fi
- Sending velocity commands
-```xml
+```bash
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: 10.0"
```
-
- Force mode
Same as velocity mode add the following line to the SDF file.
@@ -227,13 +225,11 @@ Same as velocity mode add the following line to the SDF file.
This would look almost the same as velocity mode if PID gains are tuned properly.
-Here the state of the joint is obtained using the Gazebo’s JointStatepublisher plugin. Please visit [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointStatePublisher.html#:~:text=JointStatePublisher%20Class%20Reference) for more information.
+Here the state of the joint is obtained using the Gazebo’s JointStatepublisher plugin. Please visit [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointStatePublisher.html#:~:text=JointStatePublisher%20Class%20Reference) for more information.
-
-
An example where p_gain was set to 2.0 and the joint controller failed to reach the desired velocity and behaved absurdly due to improper gains is shown below.
@@ -243,7 +239,6 @@ An example where p_gain was set to 2.0 and the joint controller failed to reach
-
## 2) JointPositionController
- Joint position controller which can be attached to a model with a reference to a single joint.
@@ -251,7 +246,7 @@ An example where p_gain was set to 2.0 and the joint controller failed to reach
JointPositionController uses a PID controller to reach a desired joint position.
-All the parameters related to this controller can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointPositionController.html#:~:text=the%20target%20position.-,System%20Parameters,-%3Cjoint_name%3E%20The).
+All the parameters related to this controller can be found [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointPositionController.html#:~:text=the%20target%20position.-,System%20Parameters,-%3Cjoint_name%3E%20The).
Commanded position(cmd_pos) can be published or subscribed at the topic: `/model//joint///cmd_pos` by default.
@@ -281,7 +276,7 @@ For this let's use the previously discussed SDF file.
2) Sending joint position command.
-```xml
+```bash
gz topic -t "/topic_name" -m gz.msgs.Double -p "data: -1.0"
```
-
## 3) JointTrajectoryController.
- Joint trajectory controller, which can be attached to a model with reference to one or more 1-axis joints to follow a trajectory.
JointTrajectoryController lets’s user specify the required position, velocity, and effort with respect to time. For velocity and position, this controller uses a PID controller.
-A detailed description and related parameter of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/5.1/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
+A detailed description and related parameter of JointTrajectoryController can be found [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointTrajectoryController.html#:~:text=Detailed%20Description).
The trajectory message can be published or subscribed at ```/model/${MODEL_NAME}/joint_trajectory``` by default.
Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classignition_1_1msgs_1_1JointTrajectory.html)
-
Example usage:
-let’s set up a new model for this example. A two-linked manipulator arm which has a total of two joints to control ( [joint_trajectory_controller](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_trajectory_controller.sdf) is the original example). Can name it as `example2.sdf`.
+Let’s set up a new model for this example. A two-linked manipulator arm which has a total of two joints to control ( [joint_trajectory_controller](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_trajectory_controller.sdf) is the original example). Can name it as `example2.sdf`.
- SDF file:
@@ -521,8 +515,8 @@ let’s set up a new model for this example. A two-linked manipulator arm which
1) Launching gazebo simulation.
-```xml
-gz sim example2.sdf
+```bash
+gz sim -v 4 -r example2.sdf
```
This is how the model will look:
@@ -563,7 +557,7 @@ Append following lines before `````` tag in SDF file.
3) Sending trajectory message (Can also change the topic name).
-```xml
+```bash
gz topic -t "topic_name" -m gz.msgs.JointTrajectory -p '
joint_names: "RR_position_control_joint1"
joint_names: "RR_position_control_joint2"
@@ -601,18 +595,17 @@ gz topic -t "topic_name" -m gz.msgs.JointTrajectory -p '
}
```
-
-Note: by default velocity and position control are disabled if one want to use these mode, they must specify the PID gains value according to usage.
+**Note**: by default velocity and position control are disabled if one want to use these mode, they must specify the PID gains value according to usage.
In case, PID gains are not specified then by default force mode will work.
4) Checking progress of commanded trajectory.
-```xml
+```bash
gz topic -e -t "/model/RR_position_control/joint_trajectory_progress"
```
From 33805a90910f226fdad6d2a29906390f590915c5 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 22:42:04 +0530
Subject: [PATCH 13/29] minor text changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 79a42cc828..5bab525fa0 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -23,9 +23,9 @@ This mode lets the user explicitly set the values of PID gains and also bounds f
**Note**: This force mode is for the user who looking to manually tune PID gains for velocity control according to a specific use case (e.g. Custom models). For general testing purposes, velocity mode will give the best results.
-Required parameters for both modes can be found [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
+All the parameters related to this controller can be found [here](https://gazebosim.org/api/gazebo/7.0/classignition_1_1gazebo_1_1systems_1_1JointController.html#:~:text=joint%20is%20actuated.-,System%20Parameters,-%3Cjoint_name%3E%20The).
-In both the modes commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel` by default.
+The commanded velocity(cmd_vel) can be published or subscribed at the topic: `/model//joint//cmd_vel` by default.
Message data type: `Double`
From 1df59596f758366987e0c9ea4c01124b8f3150c3 Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 22:45:10 +0530
Subject: [PATCH 14/29] minor changes
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
tutorials/joint_controller.md | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/tutorials/joint_controller.md b/tutorials/joint_controller.md
index 5bab525fa0..eec85561d5 100644
--- a/tutorials/joint_controller.md
+++ b/tutorials/joint_controller.md
@@ -307,7 +307,7 @@ Message type: [```JointTrajectory```](https://gazebosim.org/api/msgs/7.2/classig
Example usage:
-Let’s set up a new model for this example. A two-linked manipulator arm which has a total of two joints to control ( [joint_trajectory_controller](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_trajectory_controller.sdf) is the original example). Can name it as `example2.sdf`.
+Let’s set up a new model for this example. A two-linked manipulator arm which has a total of two joints to control ( [```joint_trajectory_controller.sdf```](https://github.com/gazebosim/gz-sim/blob/gz-sim7/examples/worlds/joint_trajectory_controller.sdf) is the original example). Name it as `example2.sdf`.
- SDF file:
From 3ebf2a7cde4fc87cf5c1b27257b5cd465b6c293d Mon Sep 17 00:00:00 2001
From: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
Date: Tue, 12 Dec 2023 22:57:19 +0530
Subject: [PATCH 15/29] Add files via upload
Signed-off-by: Yaswanth <92177410+yaswanth1701@users.noreply.github.com>
---
.../joint_controllers/JointController.png | Bin 0 -> 26562 bytes
.../JointController_Force_mode.gif | Bin 0 -> 433477 bytes
.../JointController_force_mode_bash.png | Bin 0 -> 30273 bytes
.../JointController_force_mode_bash1.png | Bin 0 -> 30219 bytes
.../JointController_vel_mode1.gif | Bin 0 -> 119792 bytes
.../JointController_vel_mode2.gif | Bin 0 -> 802527 bytes
.../JointPositionController.gif | Bin 0 -> 177433 bytes
.../JointPositionController_bash.png | Bin 0 -> 30547 bytes
.../JointTrajectoryController.gif | Bin 0 -> 211396 bytes
.../JointTrajectoryController.png | Bin 0 -> 206004 bytes
10 files changed, 0 insertions(+), 0 deletions(-)
create mode 100644 tutorials/files/joint_controllers/JointController.png
create mode 100644 tutorials/files/joint_controllers/JointController_Force_mode.gif
create mode 100644 tutorials/files/joint_controllers/JointController_force_mode_bash.png
create mode 100644 tutorials/files/joint_controllers/JointController_force_mode_bash1.png
create mode 100644 tutorials/files/joint_controllers/JointController_vel_mode1.gif
create mode 100644 tutorials/files/joint_controllers/JointController_vel_mode2.gif
create mode 100644 tutorials/files/joint_controllers/JointPositionController.gif
create mode 100644 tutorials/files/joint_controllers/JointPositionController_bash.png
create mode 100644 tutorials/files/joint_controllers/JointTrajectoryController.gif
create mode 100644 tutorials/files/joint_controllers/JointTrajectoryController.png
diff --git a/tutorials/files/joint_controllers/JointController.png b/tutorials/files/joint_controllers/JointController.png
new file mode 100644
index 0000000000000000000000000000000000000000..d773ec736036e6376f6a1a874c5daaca4c69ec55
GIT binary patch
literal 26562
zcmXtgcRbba`~T~3aAf3I2RX)Za8O9dc8tRzI}KYQTV}RSl5EFlSj9o8j7o}Zy|XeS
zQe^Ly?9lJl=lkoQ9*EnDmI+W)K9ofgq{{1QqzQ
z%G_-Y{(||L>1sk{-MkABBmn7YYnTURFOLQf{J0$c_m^_=VNfXFO&{J?7<1m~?iZSv}+{69}dV^K~{uImiC1xba0=aFAq>%kcE81w#hAFYmMFU(6-=8)M_
z{f+U~Seo^>h9B6fD(jTtKU}nQHX3H_ew0g(czRr@C|vQ+`8fs8^2&|uBBa{s+P-Ev
zy|}atW%-Z~lpcQi^udoUJ=Xq$-FGvtB2n_SdPPIe&`Xx7wW^Ogb!9QvuB=&w?gxCU
z4Ilb53unvto78zWmXs(x{q9<-nR!?#%1L1ZZR~*js`%Q|z2e)Sd)w~Pys>&7rWM`4
znuXBowQLdUHJCbC%;?SPX5}Yd=8o7$eGyDnQfJ$LZA*krFX#{~+MRyQVoEwM^ncsD
z7GLB;j1B*Y6!bKg9=auw_&8BMh$k+csJ|+JI^@*iY6)+8XZxJm$YqOOV+_>|2<|x3n2x2I&jP$mUzz&^!?YV7n{pbGY@F7
zBc3kC>xFsx!$U9gzr}?ZTsK=U`rRi~B^g`bc%{%#;*&MD(5kqyr&oN^L~OfBWVq2D
zg^uVI)=c61a3-ZuK?Lf
zb4yq&X1(DpMOA-wEQu3ID%x%RujD6n(i_i<@Xt%7Nsp(c;s`#A?_N&(sMoAp7TVt4
z`6yJ&bn-}w^^`jqjKiI`4(AE^6%(za8F8g9d!0Au>B0IKH4PvysEs7J3WXvGV
zQH5(ZQfFgL;Ez(`O*H5%?kT_@5#EL?`MPmG=$+U0L@#f6JoUB)B8^yaye}`*;87qj
z?GS>PZT<8D&7a{yDuX
zW!CNA%;2%saP)p(la%b)4;nhJ?;R1><9}S2D~*Jok`Md1MKH1dK@)UedzwlnRk7-7
zP?1@Js7PL5!UvKLj|eXnYfbCrxzjSKv`(0yq6wV~2AVrVy(e3XZM3^RRH}dN(mWc0Av!%IbuEMUqdAX<6sXRQ}m4A+(!=
z#0jlz2YHrRnCfB0__Fdm?H1*#LjN;=N4as-NcvgCdv5Iv#F4M#64UN3X}dR>*`j-v
z#rX=Oksy*FkzmGpO1gHIi0cp%X@XZH8YWB^*Ih343G<|r!#)!|8rO5)j&AdbK#TD5SKaC2@`mLr
zN>f;1eKCbf#y6894qGVFniiYoKuUpBS6=U7ZXRymQ73>Z~s~nZO=-3%BU`c^XrMq>fu}4~o-{;
zdh{UZ^NJBP!u*5ZpKu2@5oGr-IMKR}-}U9qlC`$?`AnOnf>+`CPmpgQo>%kxD|s~~
z=f1G0KhJMqja~?;cnrQprv1=XSF-DS_Ach+7c>^LOMIF#{2YnZOd)*4>XPGCv>56y
zh1G^nr0Gh_aK}~&MShGP71!~ZXQ*yFS;?dPiEfPBs8Gnf(t|}@({u-i3%Kip%GOz`
zmC8W!!2d>al4Dq;XCA#^P#0p5)y6H-SupW>cnOqeRuxJ&Ht#GAk_%Ck-`k3%|
znti|TZR9ouwR?V0=MJLjMWA?20^H8z^aj=068SQzMgA2J<6p_=bTOLi9-h;VScQ0#
zX|b{ZSzXCRrqV_G_3{A$q+rm>@jt!4Yr@WYLZ8q^u*qjaOCMFU^3!1YEF4l2qWF+;
z%{m6DT*+k&VNVH>8a!|sjCTH%Vb0l8P-T=UFAv4m5j*?oEUT#}H5T)+CFjeWBet?D
zrxaZmBQDaH++AOs*(}Yzei^xLMZIC&{nrtDRTrnJGn}tLj(?dKfM65!6qP*Baz{RB
zKnE+7rClaAa!Z>ZWZ*En^y92HfiQ?8BKbZH!
z&PSp^tn^N%%TcW*D`%E(37TM=&pb6_WsSo4x970QPE%Nox
zhj;tR`5aiQiHV$o+5Nw0xhGtG@z?+K2nqdn*91P~&z;5iOqdqfruq2!>x`b!944t2&l8IvnxAhWY({438%%wbbUWJDG)#=k}e6R4nARh(q;hQ^!^MW3ow6
zkcr3%KJF6vZWQ$OZC1Ps8OAeOxrZRGBV%!zj#$4aOfFODG$zxIq+_RyfYI0IcF_Uc
zR7Ui&W>v?0;>?|E6Z58G&7Nsfqbee&^dkuP(9>Z2WxUvVt57&r;T|o&eo6{dSrj2j
z5u{1qa5^t2kZ0%hM1eGg`Ap1KhAb~BqWV0j41z|wJK@;1ul#D1lKZpQ+lb3z`0oaO
zz@pOZIuzp9r)d7t6AsRI+#^2|fmGDO)iIZm_L8+ae1}WDsq42m--{(AXyd4A^12C?
zcObvB%K)*jY73pL!*viNsd*qlZ6(xRC?C!Ig{Zk&dZG)a*@o7u!y`)a{2hg4$p1z~
z*xrU?TphEt?r$TEKod)sa!^xA!be+b^FhaQZUZBu5t~y2_Kpyf8ZY~V3YE&>O&tt7
zOiuQj&*_6Q2^MOeTZQx2>4ZmatzSuQk*}D7Muku?VWRdWB$;ggQ-fIZPj1vS2A?P&
z?guY;+*hI1*vxfw3Srz*&gY9H|EK4*gdmz;JE>{@(iz(=28Dy{*FXp@^Mn^vyrL8I
z?K%h2={&L;k()S1O=TA3(gSmqlVMdx_DcC8DW4Wr#*k#H#t8U)h9lr1y~@5w4B;2X_rDdx#?Y!tl