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 dual joint position controller

Description: This tutorial describes how to create a dual joint position controller with a Robotis Dynamixel motors.

Keywords: Controller,Torque,Dynamixel

Tutorial Level:

Next Tutorial: Creating a joint torque controller

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 dual_motor.yaml file:

dual_motor_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller_dual_motor
        type: JointPositionControllerDual
    joint_name: dual_motor
    joint_speed: 1.17
    motor_master:
        id: 7
        init: 0
        min: -2047
        max: 2047
    motor_slave:
        id: 15

Note: Make sure that the both motors ids matches the ids assigned to your dynamixel actuator and both dynamixel motor are working on joint mode.

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_dual_motor_controller.launch file:

<launch>
    <!-- Start dual_motor joint controller -->
    <rosparam file="$(find my_dynamixel_tutorial)/dual_motor.yaml" command="load"/>
    <node name="dual_motor_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--manager=dxl_manager
                --port your_dynamixel_usb_port
                dual_motor_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_dual_motor_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 pan_controller successfully started.
[tilt_controller_spawner-1] process has finished cleanly.

If everything started up cleanly, you should see "Controller pan_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
/dual_motor_controller/command
/dual_motor_controller/state

/dual_motor_controller/command topic expects a message of type std_msgs/Float64 which sets the position of the joint.

/dual_motor_controller/state topic provides the current status of the master and the slave motor, the message type used is dynamixel_msgs/JointState.

Relevant services:

/restart_controller/ttyUSB0
/start_controller/ttyUSB0
/dual_motor_controller/ttyUSB0
/dual_motor_controller/set_compliance_margin
/dual_motor_controller/set_compliance_punch
/dual_motor_controller/set_compliance_slope
/dual_motor_controller/set_speed
/dual_motor_controller/set_torque_limit
/dual_motor_controller/torque_enable

A few services are provided that change the parameters of the joint, like position, motor torque limit, compliance margin and slope, etc.

Step 4: Moving the motor

To actually move the motor we need to publish a desired positions to /dual_motor_controller/command topic, like so:

rostopic pub -1 /dual_motor_controller/command std_msgs/Float64 -- 1.5

That's it, see the both motors move!

Learn how to control a dynamixel motor on wheel mode in next tutorial.

Wiki: dynamixel_controllers/Tutorials/Creating a dual joint position (last edited 2017-12-31 04:29:44 by HansToquica)