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 meta controller

Description: Meta controller is an action server that allows you to group up any number of motors and control it by an action client.

Tutorial Level:

Next Tutorial: Setting up Dynamixel

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 controllers 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:

joint3_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller
        type: JointPositionController
    joint_name: claw_1f
    joint_speed: 1.0
    motor:
        id: 1
        init: 0
        min: 0
        max: 4095
        
joint4_controller:
    controller:
        package: dynamixel_controllers
        module: joint_torque_controller
        type: JointTorqueController
    joint_name: traction_1f
    joint_speed: 1.0
    motor:
        id: 3
        init: 0
        min: 0
        max: 2047
        
joint5_controller:
    controller:
        package: dynamixel_controllers
        module: joint_position_controller
        type: JointPositionController
    joint_name: joint_1f
    joint_speed: 1.0
    motor:
        id: 4
        init: 0
        min: 0
        max: 4095

Note: Make sure that the motor id matches the id assigned to your dynamixel actuator.

Step2: Specify meta controller parameters

We need to create a configuration file that group up all controllers and made it an action server. Paste the text below following into joints_trajectory_controller.yaml file:

f_arm_controller:
    controller:
        package: dynamixel_controllers
        module: joint_trajectory_action_controller
        type: JointTrajectoryActionController
    joint_trajectory_action_node:
        min_velocity: 0.1
        constraints:
            goal_time: 0.25        

Note: Make sure that the motor id matches the id assigned to your dynamixel actuator. The goal_time parameter in the .yaml file changes only the time period between each action and does not interfere in the motor's velocity.

Step 3: 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_meta_controller.launch file:

<launch>
<!-- Start tilt joint controller -->
    <rosparam file="$(find my_dynamixel_tutorial)/tilt.yaml" command="load"/>
    <node name="controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--manager=dxl_manager
                --port dxl_USB0
                joint3_controller                       
                joint4_controller
                joint5_controller
                "
          output="screen"/>
          
  <!-- Start joints trajectory controller controller -->
    <rosparam file="$(find my_dynamixel_tutorial)/joints_trajectory_controller.yaml" command="load"/>
    <node name="controller_spawner_meta" pkg="dynamixel_controllers" type="controller_spawner.py"
          args="--manager=dxl_manager
                --type=meta
                f_arm_controller
                joint3_controller
                joint4_controller
                joint5_controller
               "
          output="screen"/>
</launch>

Step 4: 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_meta_controller.launch

This node will load the controller and then exit, the output will look similar to the one below:

[INFO] [WallTime: 1412948063.493818] dxl_USB0 controller_spawner: All services are up, spawning controllers...
[INFO] [WallTime: 1412948063.556084] Controller joint3_controller successfully started.
[INFO] [WallTime: 1412948063.578977] meta controller_spawner: All services are up, spawning controllers...
[WARN] [WallTime: 1412948063.608758] [f_arm_controller] not all dependencies started, still waiting for ['joint4_controller', 'joint5_controller']...
[INFO] [WallTime: 1412948063.609689] 
[WARN] [WallTime: 1412948063.626055] [f_arm_controller] not all dependencies started, still waiting for ['joint5_controller']...
[INFO] [WallTime: 1412948063.626438] Controller joint4_controller successfully started.
[INFO] [WallTime: 1412948063.720389] Controller joint5_controller successfully started.
[controller_spawner_meta-3] process has finished cleanly
log file: /home/vitor/.ros/log/d553b226-5081-11e4-ba96-0c84dc3fa970/controller_spawner_meta-3*.log
[controller_spawner-2] process has finished cleanly
log file: /home/vitor/.ros/log/d553b226-5081-11e4-ba96-0c84dc3fa970/controller_spawner-2*.log

If everything started up cleanly, you should see that all of controllers were started. If however it gets stuck on

[WARN] [WallTime: 1412948063.608758] [f_arm_controller] not all dependencies started, still waiting for ['joint4_controller', 'joint5_controller']...

replace dxl_USB0 in start_meta_controller.launch with pan_tilt_port.

Next, let's list the topics and services that our controller provides:

rostopic list

Relevant topics:

/f_arm_controller/command
/f_arm_controller/follow_joint_trajectory/cancel
/f_arm_controller/follow_joint_trajectory/feedback
/f_arm_controller/follow_joint_trajectory/goal
/f_arm_controller/follow_joint_trajectory/result
/f_arm_controller/follow_joint_trajectory/status
/f_arm_controller/state
/joint3_controller/command
/joint3_controller/state
/joint4_controller/command
/joint4_controller/state
/joint5_controller/command
/joint5_controller/state

/jointX_controller/command topic expects a message of type std_msgs/Float64 which sets the angle of the joint.

/jointX_controller/state topic provides the current status of the motor, the message type used is dynamixel_msgs/JointState.

/f_arm_controller/command /f_arm_controller/follow_joint_trajectory/cancel /f_arm_controller/follow_joint_trajectory/feedback /f_arm_controller/follow_joint_trajectory/goal /f_arm_controller/follow_joint_trajectory/result /f_arm_controller/follow_joint_trajectory/status /f_arm_controller/state topics are created by our meta controller, they are an action server so we should control it by a action client. It will be done at the next tutorial.

Relevant services:

/dxl_manager/dxl_USB0/restart_controller
/dxl_manager/dxl_USB0/start_controller
/dxl_manager/dxl_USB0/stop_controller
/dxl_manager/meta/restart_controller
/dxl_manager/meta/start_controller
/dxl_manager/meta/stop_controller
/dynamixel_manager/get_loggers
/dynamixel_manager/set_logger_level
/joint3_controller/set_compliance_margin
/joint3_controller/set_compliance_punch
/joint3_controller/set_compliance_slope
/joint3_controller/set_speed
/joint3_controller/set_torque_limit
/joint3_controller/torque_enable
/joint4_controller/set_compliance_margin
/joint4_controller/set_compliance_punch
/joint4_controller/set_compliance_slope
/joint4_controller/set_speed
/joint4_controller/set_torque_limit
/joint4_controller/torque_enable
/joint5_controller/set_compliance_margin
/joint5_controller/set_compliance_punch
/joint5_controller/set_compliance_slope
/joint5_controller/set_speed
/joint5_controller/set_torque_limit
/joint5_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.

You can change and look at the motor parameters in the next tutorial.

Wiki: dynamixel_controllers/Tutorials/Creatingmetacontroller (last edited 2021-05-18 08:20:06 by Mads Rossen)