[ros-users] Getting /smart_arm_controller/state from the UA Smart Arm Controller

Patrick Goebel patrick at casbs.stanford.edu
Mon Dec 13 17:18:23 UTC 2010


Hello ROS users,

I am trying out the UA Smart Arm Controller package with my robot which 
has a pair of AX-12+ arms, pan and tilt head servos, and a torso joint, 
all controlled on a single Dynamixel bus via a USB2Dynamixel controller. 
  I'm not sure the smart arm controller was meant to be used this way 
(as a general joint controller for the whole robot) but so far it seems 
to be working, meaning, I can move each joint by publishing to the 
appropriate topic and I can read the states of each servo on the 
appropriate topics.

The one discrepancy I have run into between the documentation and what I 
am seeing on my machine is trying to get the joint state for all joints 
as referred to in the tutorial at:

http://www.ros.org/wiki/smart_arm_controller/Tutorials/Getting%20Started%20with%20a%20Smart%20Arm

Near the bottom of the tutorial it is claimed that I can get the 
joint_states with the following command:

rostopic echo /smart_arm_controller/state

but this topic does not exist.  I can get a list of motor states with 
the command:

rostopic echo /motor_states/ttyUSB0

but this topic does not include the joint names which I will need if I 
want to see the state changes in RViz via the robot_state_publisher and 
my URDF model.

So my question is: how can I get a list of joint states including joint 
names?

Here is my full setup in case it helps:

Ubuntu 10.04 + latest ROS C Turtle Debian packages
UA Smart Arm Controller package revision 1032

Launch files:

<launch>
     <!-- Start the low-level serial driver and controller manager -->
     <include file="$(find 
ax12_controller_core)/launch/controller_manager.launch" />

     <!-- Start the pi_robot_arm controller -->
     <include file="$(find 
smart_arm_controller)/launch/pi_robot_arm.launch" />
</launch>

<launch>
     <!-- Load joint controller configuration from YAML file to 
parameter server -->
     <rosparam file="$(find 
smart_arm_controller)/config/pi_robot_arm.yaml" command="load"/>

     <!-- Start all SmartArm joint controllers -->
     <node name="smart_arm_controller_spawner" 
pkg="ax12_controller_core" type="controller_spawner.py"
           args="--port /dev/ttyUSB0
		head_pan_controller
		head_tilt_controller
		right_shoulder_pan_controller
		right_shoulder_lift_controller
		right_arm_roll_controller
		right_elbow_controller
		right_wrist_controller
		left_shoulder_pan_controller
		left_shoulder_lift_controller
		left_arm_roll_controller
		left_elbow_controller
		left_wrist_controller
		torso_controller"
           output="screen"/>
</launch>

<launch>
     <!-- Start the low-level driver manager with parameters -->
     <node name="ax12_manager" pkg="ax12_controller_core" 
type="controller_manager.py" required="true" outpu
t="screen">
         <param name="port_name" type="str" value="/dev/ttyUSB0"/>
         <param name="baud_rate" type="int" value="1000000"/>
         <param name="min_motor_id" type="int" value="1"/>
         <param name="max_motor_id" type="int" value="14"/>
         <param name="update_rate" type="int" value="10"/>
     </node>
</launch>

And the YAML file for my servos:

head_pan_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: head_pan_joint
     joint_speed: 1.17
     motor:
         id: 1
         init: 512
         min: 0
         max: 1024

head_tilt_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: head_tilt_joint
     joint_speed: 1.17
     motor:
         id: 2
         init: 512
         min: 300
         max: 800

right_shoulder_pan_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: right_shoulder_pan_joint
     joint_speed: 1.17
     motor:
         id: 3
         init: 512
         min: 0
         max: 1023

right_shoulder_lift_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: right_shoulder_lift_joint
     joint_speed: 1.17
     motor:
         id: 4
         init: 512
         min: 0
         max: 1023

right_arm_roll_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: right_arm_roll_joint
     joint_speed: 1.17
     motor:
         id: 5
         init: 512
         min: 0
         max: 1023

right_elbow_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: right_elbow_joint
     joint_speed: 1.17
     motor:
         id: 13
         init: 512
         min: 0
         max: 1023

right_wrist_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: right_wrist_joint
     joint_speed: 1.17
     motor:
         id: 6
         init: 512
         min: 0
         max: 1023

left_shoulder_pan_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: left_shoulder_pan_joint
     joint_speed: 1.17
     motor:
         id: 7
         init: 512
         min: 0
         max: 1023

left_shoulder_lift_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: left_shoulder_lift_joint
     joint_speed: 1.17
     motor:
         id: 8
         init: 512
         min: 0
         max: 1023

left_arm_roll_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: left_arm_roll_joint
     joint_speed: 1.17
     motor:
         id: 9
         init: 512
         min: 0
         max: 1023

left_elbow_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: left_elbow_joint
     joint_speed: 1.17
     motor:
         id: 12
         init: 512
         min: 0
         max: 1023

left_wrist_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: left_wrist_joint
     joint_speed: 1.17
     motor:
         id: 10
         init: 512
         min: 0
         max: 1023

torso_controller:
     controller:
         package: ax12_controller_core
         module: joint_position_controller
         type: JointPositionControllerAX12
     joint_name: torso_joint
     joint_speed: 1.17
     motor:
         id: 11
         init: 512
         min: 0
         max: 1023




More information about the ros-users mailing list