Note: This tutorial assumes that you have completed the previous tutorials: connecting to Dynamixel bus. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Creating a joint controller
Description: This tutorial describes how to create a joint controller with one or more Robotis Dynamixel motors.Tutorial Level:
Next Tutorial: Creating a dual joint position controller
Contents
All files that are created in this tutorial should be saved into my_dynamixel_tutorial package which we have created in previous tutorial.
roscd my_dynamixel_tutorial
Step1: Specify controller parameters
First we need to create a configuration file that will contain all parameters that are necessary for our controller. Paste the text below following into tilt.yaml file:
tilt_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: tilt_joint joint_speed: 1.17 motor: id: 4 init: 512 min: 0 max: 1023
Note: Make sure that the motor id matches the id assigned to your dynamixel actuator.
Now, let's understand the .yaml file. Realize that in the section "motor" there are four parameters: "id", "init", "min" and "max".
- The id parameter is arbitrary, you can choose whatever number you like it, except if you are using other dynamixels, then the dynamixel id must be unique.
- The init parameter has 4096 values, so it varies from 0 to 4095. This parameter is related to the joint initial position, hence init. Since a full rotation is 360 degrees, setting init: 1365 would leave the initial state of the motor 120 degrees from the original reference 0.
- The min parameter is the minimum rotation the motor can do, it follows the same rule as the init parameter.
- The max parameter is the maximum rotation the motor can do, it also follows the same rule as the previous parameters.
Step 2: Create a launch file
Next we need to create a launch file that will load controller parameters to the parameter server and start up the controller. Paste the following text into start_tilt_controller.launch file:
<launch> <!-- Start tilt joint controller --> <rosparam file="$(find my_dynamixel_tutorial)/tilt.yaml" command="load"/> <node name="tilt_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py" args="--manager=dxl_manager --port pan_tilt_port tilt_controller" output="screen"/> </launch>
Step 3: Start the controller
We need to start up the controller manager node first. Please refer to the previous tutorial on how to do that.
After the controller manager is up and running we finally load our controller:
roslaunch my_dynamixel_tutorial start_tilt_controller.launch
This node will load the controller and then exit, the output will look similar to the one below:
process[tilt_controller_spawner-1]: started with pid [4567] [INFO] 1295304638.205076: ttyUSB0 controller_spawner: waiting for controller_manager to startup in global namespace... [INFO] 1295304638.217088: ttyUSB0 controller_spawner: All services are up, spawning controllers... [INFO] 1295304638.345325: Controller tilt_controller successfully started. [tilt_controller_spawner-1] process has finished cleanly.
If everything started up cleanly, you should see "Controller tilt_controller successfully started." message printed to the terminal.
Next, let's list the topics and services that the Dynamixel controller provides:
rostopic list
Relevant topics:
/motor_states/ttyUSB0 /tilt_controller/command /tilt_controller/state
/tilt_controller/command topic expects a message of type std_msgs/Float64 which sets the angle of the joint.
/tilt_controller/state topic provides the current status of the motor, the message type used is dynamixel_msgs/JointState.
Relevant services:
/restart_controller/ttyUSB0 /start_controller/ttyUSB0 /stop_controller/ttyUSB0 /tilt_controller/set_compliance_margin /tilt_controller/set_compliance_punch /tilt_controller/set_compliance_slope /tilt_controller/set_speed /tilt_controller/set_torque_limit /tilt_controller/torque_enable
A few services are provided that change the parameters of the joint, like speed, motor torque limit, compliance margin and slope, etc.
Step 4: Moving the motor
To actually move the motor we need to publish a desired angle to /tilt_controller/command topic, like so:
rostopic pub -1 /tilt_controller/command std_msgs/Float64 -- 1.5
That's it, see the motor move! Want to control two motors in position mode? Learn how to do it in the next tutorial.