This page serves as a lookup reference for all the hardware and functionality for the SKD. The main interface of the SDK is via ROS Topics and Services, which you will find listed and described below along with other core information needed to interface with the robot.


Contents


ROS Topic API Reference


Python Code API


For the Robot Interface Python classes (built on top of the ROS API), please see the Code API Reference page.


Robot

 

Enable Robot

 

Be sure that you 'Enable' the robot before attempting to control any of the motors. The easiest method for controlling the robot is to use the enable_robot.py ROS executable found in the following example: Enable Robot Script

 

Robot State


/robot/state (intera_core_msgs/AssemblyState) Subscribe to the Robot State for the enabled and error state of the robot hardware itself. It also includes information on the EStop. The robot must be enabled (enabled: true) in order to move the robot. Use the Enable Robot Script, or the "Enable Robot Topic" below, to enable the robot. It is possible for the robot to have non-fatal errors, so error can be true while enabled is also true. For more complete information on robot state, see E-STOP and Enable Robot.


Enable Robot


/robot/set_super_enable (std_msgs/Bool) data: true to Enable robot motors; false to disable. You can check the Robot State Topic to see if the robot enabled properly or if it has an error.


Reset Robot State


/robot/set_super_reset (std_msgs/Empty) Publish an Empty message to reset the state after an error. A reset will clear all pre-existing errors and the state (it will disable).


Robot Description (URDF)


Sawyer automatically builds an appropriate URDF (Unified Robot Description Format) on boot and loads it onto the ROS Parameter Server, under the ROS parameter name /robot_description. From here, it is accessible by rviz, tf and other ROS utilities that use the URDF.

The Unified Robot Description Format (URDF) is the standard ROS XML representation of the robot model (kinematics, dynamics, sensors) describing Sawyer.

Sawyer generates his URDF dynamically on robot startup. This model is updated when any gripper is attached or detached, an object is 'grasped' or released and its mass is compensated for, and when new urdf segments are provided/commanded to the gripper plugins. As of SDK versions >= 1.0.0 Sawyer's internal robot model, is loaded to the parameter server on the topic /robot_description

The default URDF for Sawyer is available in the intera_common repository. The package sawyer_description contains the URDF and accompanying meshes.

  

Getting a Copy of the URDF from the parameter server


You can now get the current URDF describing your Sawyer.

From a properly initialized Sawyer environment, export the URDF from the /robot_description parameter on the ROS parameter server where it is stored, to a file of your choice (ex: sawyer_urdf.xml):


$ rosparam get -p /robot_description | tail -n +2 > sawyer_urdf.xml

 

The -p outputs the parameter using pretty print. The output urdf is piped through the tail command first to remove a dummy first line - an artifact of the pretty print.

Tip: You can check that you now have a proper URDF by running:


$ rosrun urdfdom check_urdf sawyer_urdf.xml

 

Robot State Publisher

 

The URDF is used by Sawyer's Robot State Publishers to create a tree of transforms (tfs). In fact, Sawyer has two of such publishers: robot_ref_publisher: publishes transforms that reflect the commanded robot state. robot_state_publisher: publishes transforms that reflect the measured state of the robot.

These robot publishers live internal to Sawyer and are accessible to the RSDK over ROS. The "ref" tfs are used by the robot internals, but you may find them useful to see where the robot will move at the next timestep. Otherwise, be sure to use the non-"ref" transforms if you're only interested in the Sawyer's current state.

  

Getting a Copy of the URDF Dynamically

 

Sawyer generates the URDF dynamically on initialization, based on the attached arm. In some cases, users may want to get the current URDF off the robot. From a working Sawyer RSDK environment, export the URDF from the /robot_description parameter on the ROS parameter server where it is stored, to a file of your choice (ex: sawyer_urdf.xml):


$ rosparam get -p /robot_description | tail -n +2 > sawyer_urdf.xml

The -p outputs the parameter using pretty print. The output urdf is piped through the tail command first to remove a dummy first line - an artifact of the pretty print.


Tip: You can check that you now have a proper URDF by running:


$ rosrun urdf_parser check_urdf sawyer_urdf.xml

 

If this doesn't work, you can just remove the tail command and use a text editor to manually remove the first few lines before the actual xml (all the lines before <?xml version="1.0" ?>).


$ rosparam get -p /robot_description > sawyer_urdf.xml
$ head sawyer_urdf.xml
 |  
      <?xml version="1.0" ?>  
      <!-- =================================================================================== -->  
      <!-- |    This document was autogenerated by xacro from sawyerp2.urdf.xacro            | -->  
    ...  
$ gedit sawyer_urdf.xml &
$ head sawyer_urdf.xml
      <?xml version="1.0" ?>  
      <!-- =================================================================================== -->  
      <!-- |    This document was autogenerated by xacro from sawyerp2.urdf.xacro            | -->  
    ...


Movement


Joints

 

Sawyer has 7 joints (DoF) in arm and one more joint in its head (side-to-side panning). The control for the head is done separately from the arm; however, you can read the current joint states (position, velocity, and effort) for all the joints on arm and head by subscribing to one topic: /robot/joint_states (sensor_msgs-JointState) where the units for the position of a joint are in (rad), the units of velocity are in (rad/s) and the units of effort in each joint is in (Nm).


Arm Joints


The following sections cover the arm joints sensing and control in more detail: Arm Joints.


Head Joints


The head state topic will give you the current pan angle (side-to-side) of the head and report boolean status flags if the robot is currently moving its head.


Note: Flags may not report 'true' values until after the first respective movement command is sent.


Component ID:head_pan


Head State:
/robot/head/head_state (intera_core_msgs-HeadState). pan field gives you the current angle (radians) of the head. 0 is forward, -pi/2 to Sawyer's right, and +pi/2 to Sawyer's left. isPanning is boolean field that will switch to True while the robot is executing a command.

Note: The isPanning field is initialized to True upon startup and will update thereafter.


Head (Joint) State:
/robot/joint_states (sensor_msgs-JointState).The position of the head may also be determined from the joint_state message.

 

Head Movement Control


Pan Head:


/robot/head/command_head_pan (intera_core_msgs-HeadPanCommand) target sets the target angle. 0.0 is straight ahead. speed is an integer from [0-100], 100 = max speed. Setting an angle in the command_head_pan topic does not gurantee the head will get to that position. There is a small deband around the reference angle around the order of +/- 0.12 radians.


Example


# Check head position/state: 
$ rostopic echo /robot/head/head_state
# Move (pan) head side-to-side: 
$ rostopic pub /robot/head/command_head_pan intera_core_msgs/HeadPanCommand -- 0.0 100

 

Cartesian Endpoint

 

Published at 100 Hz, the endpoint state topic provides the current Cartesian Position, Velocity and Effort at the endpoint for either limb.

 

Endpoint State

 

Endpoint State: /robot/limb/right/endpoint_state (intera_core_msgs-EndpointState). The endpoint state message provides the current position/orientation pose, linear/angular velocity, and force/torque effort of the robot end-effector at 100 Hz. Pose is in Meters, Velocity in m/s, Effort in Nm. The robot's "endpoint" is definied as the right_gripper tf frame. This frame is updated dynamically when gripper is connected to the robot . The URDF on the parameter server will now update when the Robot Model is updated by Gripper changes. Check the ROS Parameter for an updated copy of the URDF, especially before using IK or motion planners, such as MoveIt!.


Kinematics Solver Service


The following sections cover the Forward Kinematics Solver Service and Inverse Kinematics Solver Service in more detail: Kinematics Solvers


Gripper (End-Effector)


Before using an End-Effector, or Gripper, you must first send the calibration command. You can check whether the gripper has been calibrated yet by echoing on the gripper state topic for that hand. Once calibrated, gripper can be controlled using the simplified command_grip and command_release topics, or using the more direct command_set topic. For more information on using the gripper, see the Gripper Example Program.


Gripper Configuration


(intera_core_msgs-IOComponentCommand)


Calibrate Gripper


Publish an IO Command message to calibrate a new gripper by set signal calibrate to True. Gripper should open and close once. The calibrated field of the gripper state topic will also update to '1' after successful calibration. Once calibrated, the gripper will not calibrate again unless the command reset message is sent, or the robot is restarted.


Reset Gripper


Publish an IO Command message to reset the gripper state by set signal reboot to True. The calibrated field of the gripper state message will reset to '0'.

 

Gripper State


/io/end_effector/state The io signal calibrated field must be true (1) before you can control the gripper. Use the IO command to calibrate the gripper. The gripper state message will also give you the current position, force, and if the gripper is current moving. Position is from [0.0-100.0] [close-open].

 

Simple Gripper Control

 

Simple Gripper Close
/io/end_effector/command the signal 'position_m' value to MIN_POSITION: 0.0. Publish an IO Command message to grip.

Simple Gripper Open
/io/end_effector/command the signal 'position_m' value to MAX_POSITION: 0.041667. Publish an IO Command message to release.


Sensors


Accelerometer


The robot hand has a 3-axis accelerometer located inside the cuff, in the same plane as the gripper electrical connection header. The positive z-axis points back 'up' the arm (towards the previous wrist joint, j6). The positive x-axis points towards the direction of gripper, and the y-axis points towards the cuff buttons, using standard Right-Hand-Rule notation.


Component IDs:
right_accelerometer


Accelerometer State:
/robot/accelerometer/<component_id>/state(sensor_msgs-ImuMessage)

Acceleration values (in m/s^2) are published under linear_acceleration for the x, y, and z axes. The force of gravity is NOT compensated for.


names: ['right_accelerometer']
states: 
  - 
    header: 
      seq: 120921
      stamp: 
        secs: 0
        nsecs: 0
      frame_id: ''
    orientation: 
      x: 0.0
      y: 0.0
      z: 0.0
      w: 0.0
    orientation_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    angular_velocity: 
      x: 0.0
      y: 0.0
      z: 0.0
    angular_velocity_covariance: [-1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    linear_acceleration: 
      x: 0.0
      y: 0.0
      z: 0.0
    linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

 

Cameras

 

You can access Sawyer's hand camera and the head camera using the standard ROS image types and image_transport mechanism listed below. You can use the ROS Services to open, close, and configure each of the cameras. See the Camera Image Display Example for more information on using the cameras. Useful tools for using cameras in ROS include rviz Camera Display.


IMPORTANT: You can only have one open at a time at standard resolutions, due to bandwidth limitations.


Component IDs: right_hand_camera, head_camera

Camera Published Topics

Raw Image: /internal_camera/<component_id>/image_raw (sensor_msgs-Image)

Camera Intrinsics: /internal_camera/<component_id>/camera_info (sensor_msgs-CameraInfo)

Rectify Color Image: /internal_camera/head_camera/image_rect_color (image_proc)

Rectify Image: /internal_camera/right_hand_camera/image_rect (image_proc)

 

Head Display


Images can be displayed on Sawyer's LCD screen by publishing the image data as a ROS sensor_msgs/Image.

Display Image/robot/head_display (sensor_msgs-Image).

Publish image data as a ROS Image message to update the display. The screen resolution is 1024 x 600. Images smaller than this will appear in the top-left corner. There are dedicated ROS packages for working with and sending ROS Image messages, including image_transport and image_pipeline. Useful tools for working with images in ROS include Image_view and republish. Also see camera_drivers for assistance working with your own cameras.

For more information on displaying images to Sawyer's LCD screen, see the Head Display Image Example.


Inputs and Outputs



There are two Navigators on Sawyer's body: one on side of the body and one on the arm. Each Navigator is comprised of three push buttons, one of which is also an indexing scroll wheel, and one set of white LED light.

Component IDs: right, head

Read Button States:/io/robot/navigator/state (intera_core_msgs-IODeviceStatus)

Wheel State:/io/robot/navigator/state (intera_core_msgs-IODeviceStatus)

Command Buttons:/io/robot/navigator/command (intera_core_msga-IOComponentCommand)

The states of the push buttons are the values type in integer at data area. For the wheel on navigator, the data field returns an integer between [0-255]. Each physical 'click' of the wheel corresponds to a +/-1 increment. The value will loop when it goes above or below the bounds. The values have corresponding meaning: 0:'OFF', 1:'CLICK', 2:'LONG_PRESS', 3:'DOUBLE_CLICK'

 

  • <Component ID>_button_ok: The circular button in the middle of the navigator.
  • <Component ID>_button_back: The button above the OK button, typically with a 'Back' arrow symbol.
  • <Component ID>_button_show: The "Rethink Button", is above the OK button, next to back button and typically is labeled with the Rethink logo.
  • <Component ID>_button_triangle(the 'X' button): The button below circle button and square button.
  • <Component ID>_button_circle: The button labeled with a circle, next to the square button.
  • <Component ID>_button_square: The button labeled with a square, next to the circle button.
  • <Component ID>_wheel: The wheel of circular button in the middle of the navigator.

 

Cuff Buttons


There are two buttons and one touch sensor in the cuff of the hand: cuff button, OK button and cuff grasp button. The state of each button is published in a DigitalIOState message under its own topic (DigitalIOState constants: PRESSED==1, UNPRESSED==0). Integer data will read PRESSED (1) when the cuff sensor is squeezed, and UNPRESSED (0) otherwise.

Component IDs: right_cuff, right_button_lower, right_button_upper.

Read Button Squeezed: /io/robot/cuff/state (intera_core_msgs-IODeviceStatus)

Command Cuff:/io/robot/cuff/command(intera_core_msga-IOComponentCommand)

 

Lights


The head LEDs at the top of Sawyer's head, and navigator LEDs are inside of navigator.

To get state or set command to HALO and Navigator LEDS, we are using IODeviceInterface to config, status and command topics. The data are type in bool in data area.

Lights Component IDs:
head_red_light, head_blue_light, head_green_light, right_hand_blue_light, right_hand_green_light, right_hand_red_light

LEDs State: /io/robot/robot/state (intera_core_msgs-IODeviceStatus)

Command Light:/io/robot/robot/command(intera_core_msga-IOComponentCommand)