!

Note: This tutorial assumes that you have completed the previous tutorials: Creating a joint controller.
(!) 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 multi turn joint controller

Description: This tutorial describes how to configure the joint controller to multi turn mode.

Tutorial Level: INTERMEDIATE

Next Tutorial: Creating a dynamixel action client controller

The multiturn mode

The multiturn mode allows the servo to receive a goal position value bigger than 4095 (4095 is equivalent to 2pi, since this is its resolution). With multiturn mode enabled the servo will support a maximum goal position range equivalent to 6 or 7 turns, in this example the reference will be the dynamixel MX-28, that when in multi turn mode initial value is 0 and range is from -24576 to 24576.

Multiturn mode is available only on some servos, please check your servo documentation to check if it is available and the limits.

Values and Messages

It's important to reinforce that, when you are giving the servo parameters in the .yaml file, the angle limits are represented by the dynamixel binary value (in the first tutorial set as 0/4095), while the value that in published in the joint_controller/command is in rad. So, if you want the servo to have 1 turn of limit and you will only publish positive position values , the limits will be set as 0/4095, and the initial position of the servo will be considered as 0, and if you want the servo to go to the position equivalent to its maximum(4095) the value published will be around 6.28 (2pi).

Configuring the multi turn mode

There are many ways to configure your dynamixel to multiturn mode, the ros package dynamixel_driver, included in dynamixel_motor, provides nodes that configures its limits, but there are some alternatives like Mixcell , and Dynamixel Workbench and Smart Servo Framework.

Config file

Assuming that you want to give your servo max turn limits, and that it is already configured as multiturn mode and its ID is 1, the config file should look like this.

tilt_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller
        type: JointPositionController
    joint_name: tilt_joint
    joint_speed: 1.0
    motor:
        id: 1
        init: 24576
        min: 0
        max: 49152

Understanding the limits

The initial value as set as 24576, it will be considered as our zero position, if we send a negative goal position the servo will spin in the CCW direction, while if we send a positive value it will move in the CW direction, since the negative and positive values have their reference in the 24576. The maximum value achieve by the servo will be around 37.7, since it is the turn limit multiplied by 2pi.

        init: 24576
        min: 0
        max: 49152

Running

Launch the controller_manager.

roslaunch my_dynamixel_tutorial controller_manager.launch

Launch the tilt_controller

roslaunch my_dynamixel_tutorial start_tilt_controller.launch

Move it

To move it , it's the same thing as the past tutorial, but now it can receives values bigger than 2pi.

rostopic pub -1 /tilt_controller/command std_msgs/Float64 -- 9

Wiki: dynamixel_controllers/Tutorials/CreatingAMultiTurnJointController (last edited 2017-11-08 02:16:37 by HansToquica)