Note: This tutorial assumes that you have completed the previous tutorials: connecting to Dynamixel bus.

Creating a joint controller

Description: This tutorial describes how to create a joint controller with one or more Robotis Dynamixel motors.

Tutorial Level:

All files that are created in this tutorial should be saved into dynamixel_tutorials package which we have created in previous tutorial.

roscd dynamixel_tutorials

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

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 dynamixel_tutorials)/tilt.yaml" command="load"/>
    <node name="tilt_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--port /dev/ttyUSB0
                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 dynamixel_tutorials 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!

Wiki: dynamixel_controllers/Tutorials/CreatingJointPositionController (last edited 2011-06-26 00:01:24 by AntonsRebguns)