Only released in EOL distros:
Package Summary
Configuration for CARLS's Head Dynamixel Servo
- Maintainer status: maintained
- Maintainer: David Kent <dekent AT gatech DOT edu>
- Author: Chris Dunkers <cmdunkers AT wpi DOT edu>, David Kent <dekent AT gatech DOT edu>
- License: BSD
- Bug / feature tracker: https://github.com/GT-RAIL/carl_dynamixel/issues
- Source: git https://github.com/GT-RAIL/carl_bot.git (branch: master)
Contents
Newly proposed, mistyped, or obsolete package. Could not find package "carl_dynamixel" in rosdoc: /var/www/docs.ros.org/en/api/carl_dynamixel/manifest.yaml
About
The carl_dynamixel package is a package which launches the correct nodes and controllers from the 'dynamixel_motors' package. It also has a sensor_msgs/JointState publisher.
Nodes
back_joint_node
back_joint_node will take the position information and publish it as a 'sensor_msgs/JointState'Subscribed Topics
motor_states/back_port ('dynamixel_msgs/MotorStateList')- a list of the motor states connected to the dynamixelUSB controller.
Published Topics
dynamixel_back ('sensor_msgs/JointState')- publishes the joint state information for all of the motors connected to the dynamixelUSB controller.
Parameters
back_servos/num_servos (int)- number of servos connected to the dynamixelUSB
- the id number of the first servo connected
- the link_name number of the first servo connected
front_joint_node
front_joint_node will take the position information and publish it as a 'sensor_msgs/JointState'Subscribed Topics
motor_states/front_port ('dynamixel_msgs/MotorStateList')- a list of the motor states connected to the dynamixelUSB controller.
Published Topics
dynamixel_front ('sensor_msgs/JointState')- publishes the joint state information for all of the motors connected to the dynamixelUSB controller.
Parameters
front_servos/num_servos (int)- number of servos connected to the dynamixelUSB
- the id number of the first servo connected
- the link_name number of the first servo connected
servo_pan_tilt
servo_pan_tilt allows velocity-based panning and tilting for the servos.Subscribed Topics
asus_controller/tilt ('std_msgs/Float64')- Tilt command subscriber (rad/s) for the back servo (asus depth sensor mount).
- Pan command subscriber (rad/s) for the front servo (creative depth sensor mount).
- Joint state updates for the back servo.
- Joint state updates for the front servo.
Published Topics
asus_controller/command ('std_msgs/Float64')- Position command (rad) for the back servo (asus depth sensor mount).
- Position command (rad) for the front servo (creative depth sensor mount).
Services
asus_controller/look_at_point (carl_dynamixel/LookAtPoint)- Center asus camera on a given point.
- Center asus camera on a given coordinate frame.
Installation
Source
To install from source, execute the following:
Ubuntu Package
To install the Ubuntu package, execute the following:
sudo apt-get install ros-indigo-carl-bot
Startup
The carl_dynamixel package contains a carl_servos.launch This file launches an instance of the dynamixel_manager and tilt_controller_spawner nodes from the 'dynamixel_motor' metapackage. It also launches the 'back_joints_node' and front_joints_node, as well as the servo_pan_tilt node for velocity commands. To launch these nodes, the following command can be used:
roslaunch carl_dynamixel carl_servos.launch
Once this launches the following topics becomes available:
Available Topics
the topics to which the launch files publishes and subscribes.Subscribed Topics
asus_controller/command ('std_msgs/Float64')- the command in radians to which the servo on the asus_controller should go. 0 radians = 512 out of the possible 1023. Commands range from -2.618 to 2.618 when the servo can traverse its full range.
- the command in radians to which the servo on the asus_controller should go. 0 radians = 512 out of the possible 1023. Commands range from -2.618 to 2.618 when the servo can traverse its full range.
- Velocity command (rad/s) to move the back servo.
- Velocity command (rad/s) to move the front servo.
Published Topics
motor_states/back_port ('dynamixel_msgs/MotorStateList')- a list of the motor states connected to the dynamixelUSB controller at back of robot.
- a list of the motor states connected to the dynamixelUSB controller at front of robot.
- information about the servo associated with the asus_controller
- information about the servo associated with the creative_controller
Expansion
This package can support up to 5 servos per USB device.
Wiring
To add a servo to the USB device simply attach the 3-pin wire, on the right connector of the servo, to an open connector on the power distribution board.
Code
To make sure the newly attached servo has its 'sensor_msgs/JointState' published and that it can be controlled a controller and the joint state information needs to be added.
Controller
Just by attaching the servo, some information will automatically be published to the 'motor_states/<port>' topic, where the port is the specific USBDynamixel it is plugged into. To make sure the servo can be moved a YAML file needs to be made. Copy and paste the following code into carl_dynamixel/config/example.yaml
example_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController joint_name: example_joint joint_speed: 0.5 motor: id: 1 init: 512 min: 0 max: 1023
The id for the servo can be found from the 'motor_states/<port>' topic
Now add to the launch file:
<!-- Start example joint controller --> <rosparam file="$(find carl_dynamixel)/config/example.yaml" command="load"/> <node name="example_controller_spawner" pkg="dynamixel_controllers" type="controller_spawner.py" args="--manager=dxl_manager --port back_port example_controller" output="screen"/>
Now launch the file and the new servo should have specific joint information published on the 'example_controller/state' topic and publishing a Float64 to the 'example_controller/command' will move the servo to that position.
Joint State
Joint state publishers are already set up, however, to add a new servo the following lines need to be added to either back_servos.yaml or front_servos.yaml depending on which USB port they are plugged into.
"2": id: 2 link_name: joint_2
Also the variable num_servos should be changed to match the number of servos.
The following is an example of the modified back_servos.yaml file.
back_servos: num_servos: 3 "1": id: 1 link_name: asus_servo_asus_servo_arm_joint "2": id: 2 link_name: joint_2 "3": id: 12 link_name: joint_3
Support
Please send bug reports to the GitHub Issue Tracker. Feel free to contact me at any point with questions and comments.