Contents
Available Joint Controllers
ROS API
API Stability
- ROS API is UNREVIEWED but UNSTABLE
- Python API is UNREVIEWED and UNSTABLE
controller_manager.py
Manages a single serial connection to Dynamixel servo network. This node provides services to start, stop and restart joint controllers. There can be several instances of controller_manager running at the same time, managing multiple serial connections.Services
start_controller/serial_port_name (dynamixel_controllers/StartController)- Start stopped joint controller managed by this controller manager.
- Stop running joint controller managed by this controller manager.
- Restart running joint controller managed by this controller manager (a shortcut to running Stop and then Start).
Parameters
~port_name (str, default: /dev/ttyUSB0)- Path to serial port that the Dynamixel motors are connected to.
- Baud rate to use (make sure that the motors are set to the same baud rate, otherwise the controller_manager node will not be able to find any motors).
- The valid motor id range is 1 - 253. Setting min_motor_id to your actual range of motor ids will cut node startup time.
- The valid motor id range is 1 - 253. Setting max_motor_id to your actual range of motor ids will cut node startup time.
- The rate (in Hz) at which motors will publish their status (current position, velocity, temperature, load, etc.) Setting this to 0 will turn off the feedback.
controller_spawner.py
Parameters
joint_controller_name/controller/package (str)- ROS package name that contains the controller code.
- Specific file (python module) within a package that contains the controller code.
- Class name within module that implements JointController interface.
Common Joint Controller Interface
Subscribed Topics
joint_controller_name/command (std_msgs/Float64)- Listens for a joint angle (in radians) to be sent to the controller.
- Listens for motor status feedback published by low level driver.
Published Topics
joint_controller_name/state (dynamixel_msgs/JointState)- Provides current joint status information (current goal, position, velocity, load, etc.)
Services
joint_controller_name/set_speed (dynamixel_controllers/SetSpeed)- Change the current velocity of the joint (specified in radians per second).
- Turn joint torque on or off.
- Change the level of torque near goal position (see Dynamixel documentation for more details).
- Change allowable error between goal position and present position (see Dynamixel documentation for more details).
- Change minimum amount of torque at goal position (see Dynamixel documentation for more details).
- Change the maximum amount of torque (see Dynamixel documentation for more details).
Parameters
joint_controller_name/joint_name (str)- Name of the joint this controller is responsible for.
- Maximum joint velocity (specified in radians per second).
- Default joint velocity (specified in radians per second).
- Dynamixel motor compliance slope (acceptable values are 0 - 254).
- Dynamixel motor compliance margin (acceptable values are 0 - 255).
- Dynamixel motor punch (acceptable values are 0 - 255).
- Dynamixel motor maximum torque (acceptable values are 0.0 - 1.0, with 0 meaning no torque and 1 meaning maximum torque).
Additional Controller Configuration
Every joint controller can add additional configuration parameters (e.g. dual motor controllers need to know the low level configuration of both motors). See joint controllers page for a list of controllers included in the dynamixel_controllers package and their configuration parameters.
Example Controller Configuration
Could not fetch external code from 'http://ua-ros-pkg.googlecode.com/svn/stacks/dynamixel_motor/tags/diamondback/dynamixel_tutorials/config/dynamixel_joint_controllers.yaml': HTTP Error 404: Not Found
Example Application
Below is an example of dynamixel_motor stack in use on the Wubble robot. dynamixel_motor stack controls the head pan and tilt, the tilt of the laser and every joint in the 7-DOF arm.