[Documentation] [TitleIndex] [WordIndex

When using the Shadow hand you may wish to tune the PID parameters for different joints to meet your requirements. This only applies to the real hardware, you should not need to alter these parameters in simulation.

For the default mixed position and velocity controllers, you can tune the following parameters:

Using the GUI

The most straightforward way to adjust controller parameters is using the Shadow Robot controller plugins in rqt_gui. This is started by running:

$ rosrun rqt_gui rqt_gui

The under the plugins menu go to Shadow Robot > Controllers > Controller Tuner. From here select the type of controllers you want to tune, then you can easily adjust individual joint parameters update them, and save them to file.

Using a ROS Node

You can update the controller parameters from your node. Here is a simple example:

   1 import roslib; roslib.load_manifest('sr_hand')
   2 import rospy
   3 from sr_robot_msgs.srv import *
   4 
   5 def cont_param_client():
   6     rospy.wait_for_service('/sh_ffj0_mixed_position_velocity_controller/set_gains')
   7     try:
   8         ffj0_gains = rospy.ServiceProxy('/sh_ffj0_mixed_position_velocity_controller/set_gains', SetMixedPositionVelocityPidGains)
   9         ffj0_gains(0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 1)
  10     except rospy.ServiceException, e:
  11         print "Service call failed: %s"%e
  12 
  13 if __name__ == "__main__":
  14     try:
  15         cont_param_client()
  16     except rospy.ROSInterruptException: pass

Using the Command Line

If you do not wish to use the GUI you can use the following method to adjust controllers:

From Fuerte onwards, each joint controller has its own set_gains service to adjust these parameters. Once the system is up and running, entering the following command will show you the running services:

$ rosservice list

You can easily update parameters for testing individual controllers by calling the appropriate service from the command line, however these will not be saved the next time the system is started. For example (with nonsense values):

$ rosservice call /sh_ffj0_mixed_position_velocity_controller/set_gains 0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 0.5 1

You can then check the parameters have been updated by viewing the appropriate controller state topic:

$ rostopic echo /sh_ffj0_mixed_position_velocity_controller/state

Saving the Values

Once you have decided on the best controller values for your application, you can adjust them in the yaml file from which they are loaded when the controllers start. It is advisable to create a backup of these files before you adjust them, as they will have already been tuned for your specific hardware.

You can cd to the correct directory as follows:

$ roscd sr_ethercat_hand_config/controls/host

Here you can find the yaml files containing parameters for each of the different types of controllers.


2023-10-28 13:05