From sdk-wiki
Jump to: navigation, search

Robot API

ROS Topic API Reference

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


Python Code API
For the baxter_interface Python classes (built on top of the ROS API), please see the Code API Reference page at: http://api.rethinkrobotics.com


Robot Movement Sensors+ I/O

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.

Robot State
/robot/state (baxter_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 Tool, 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 Robot State and EStop

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)

Baxter 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. If you want to grab a copy of the actual URDF xml file yourself, see the How To's.

Joints

Baxter has 7 joints (DoF) in each of its two arms and two more joints in its head (side-to-side panning, and binary, up-down nodding). The control for the head is done separately from the arms; however, you can read the current joint states (position, velocity, and effort) for all the joints on both arms 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).

The following sections cover the individual joint sensing and control in more detail:

Arm Joints

Component IDs:
left_e0, left_e1, left_s0, left_s1, left_w0, left_w1, left_w2, right_e0, right_e1, right_s0, right_s1, right_w0, right_w1, right_w2

Arm Joint States

/robot/joint_states (sensor_msgs-JointState)

  • name[i]: '<component_id>' of i-th joint in message value arrays.
  • position[i]: position of joint i rad
  • velocity[i]: velocity of joint i in rad/s
  • effort[i]: effort applied in joint i in Nm

Joint states are published by the robot_state_publisher and are updated with information from the sensors for every cycle.

Set Joint State Publishing Rate
/robot/joint_state_publish_rate (std_msgs-UInt16)

  • The rate at which the joints are published can be controlled by publishing a frequency on this topic.
  • Default rate is 100Hz; Maximum is 1000Hz.
  • Note: In current version of SDK (v0.6.0), there is a known bug where high rates will cause many topics to lag and become unresponsive.

Arm Joint Control

There are currently four modes for controlling the arms: Joint Position Mode, Joint Velocity Mode, and Joint Torque Mode, and 'raw' Joint Position Mode.

Alternatively, a joint trajectory action server has been created in support of timestamped joint position trajectories using the ROS standard joint trajectory action.

For more information on joint control, see the following movement example programs.

Joint Control Mode

Each arm can be in independent control modes by publishing the desired control mode to the topic for the appropriate arm.

Position Mode

The first is Position Mode, in which users publish target joint angles for given joints and the internal controller drives the arm to the published angles.

Velocity Mode

Warning: Advanced Control Mode. In Velocity Control Mode, users publish velocities for given joints and the joints will move at the specified velocity.

Torque Mode

Warning: Advanced Control Mode. In Torque Control Mode, users publish torques for given joints and the joints will move at the specified torque.

"Raw" Position Mode

Warning: Advanced Control Mode. In 'raw' Position Control Mode, users publish desired joint positions. Where these commands would typically be modified in traditional 'Position Mode', these commands are passed directly to the Joint Controller Boards (JCBs). The only limitation placed on 'raw' joint position commands is a maximum delta from current position to avoid over-torque errors from the JCBs as they try to reach the specified command at the 1000Hz period.

Switching Modes
/robot/limb/<side>/joint_command (baxter_core_msgs/JointCommand)

  • Mode is set implicitly by specifying the mode in the command message. Publish a JointCommand message to the joint_command topic for a given arm to set the arm into the desired control mode.
  • Constants for each mode are defined in the JointCommand message type.

Joint Trajectory Action

The Joint Trajectory Action provides an ROS action interface for tracking trajectory execution.

The joint trajectory action server provides an action interface for execution of trajectories requested by the client, known as a Goal* request. The joint trajectory action server then executes the request trajectory communicating the *Result response. The actionlib (action server/client interface) package differs from ROS services, simple request/response interface, in that actions allow mid-execution cancellation, they can also provide feedback during execution as to the progress of the Goal request.

Joint Trajectory Action Server
/robot/limb/<limb>/follow_joint_trajectory/cancel
/robot/limb/<limb>/follow_joint_trajectory/feedback
/robot/limb/<limb>/follow_joint_trajectory/goal
/robot/limb/<limb>/follow_joint_trajectory/result
/robot/limb/<limb>/follow_joint_trajectory/status

Usage:

    # Verify that the robot is enabled:
    $ rosrun baxter_tools enable_robot.py
    # Start the joint trajectory action server:
    $ rosrun baxter_interface joint_trajectory_action_server.py

Please see the simple joint trajectory example or joint trajectory playback example for examples of creating a client of this action server and requesting a joint trajectory.

Parameters:

The joint trajectory action server provides a number of parameters which describe it's behavior during the trajectory execution. These were largely designed to follow these standards.

Note: All of these parameters will be initialized on startup of the trajectory_controller.py if they were not previously specified. /rethink_rsdk_joint_trajectory_controller/<joint_name>__kp The proportional gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/<joint_name>__kd The derivative gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/<joint_name>__ki The integral gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/goal_time (double, default: 0.0) The amount of time (in seconds) that the controller is permitted to be late to the goal. If goal_time has passed and the controller still has not reached the final position (within the parameters described by /rethink_rsdk_joint_trajectory_controller/<joint_name>_goal, then the goal is aborted.

/rethink_rsdk_joint_trajectory_controller/<joint>_goal (double, default: -1.0) The maximum final error for <joint> for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

/rethink_rsdk_joint_trajectory_controller/trajectory (double, default: -1.0) The maximum error for <joint> at any point during execution for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

Dynamic Reconfigure GUI is suggest for use with ROS Distributions >=Indigo for setting these parameters.

   # Start the dynamic reconfigure GUI:
   $ rosrun rqt_reconfigure rqt_reconfigure

Expand the joint trajectory controller's parameters by choosing rethink_rsdk_joint_trajectory_controller from the left menu. Use the sliders/input fields to specify these parameters dynamically.

Alternatively, these parameters can be set via a YAML file, command line, or programmatically (rospy, roscpp).

Collision Avoidance

Warning: RETHINK ROBOTICS DISCLAIMS COMPLIANCE BY THE PRODUCTS WITH ANSI, ISO OR OTHER INDUSTRIAL ROBOT SAFETY STANDARDS. RETHINK’S PRODUCTS INCLUDE CERTAIN SAFETY AND/OR COLLISION DETECTION TECHNOLOGY TO PREVENT POSSIBLE INJURY FROM USE OF THE PRODUCTS. THE USER ACKNOWLEDGES THAT HE/SHE HAS THE ABILITY TO DISABLE CERTAIN SAFETY MECHANISMS INCLUDED IN THE PRODUCTS, AND IF DISABLED BY USER, USER ASSUMES ALL RESPONSIBILITY FOR DAMAGE AND/OR HARM CAUSED BY THE PRODUCTS AND AGREES TO INDEMNIFY RETHINK ROBOTICS FROM ALL LIABILITY RELATING TO SUCH DAMAGE OR HARM.

In certain situations, collision avoidance (forces applied to the joints to avoid self collision) are undesirable.

Torso Collision Avoidance
/robot/limb/right/suppress_collision_avoidance (std_msgs-Empty)

  • To disable torso self collision avoidance, a std_msgs/Empty message must be published at a rate greater than 5 Hz.


For additional information on joint control, see the Joint Position Example, Joint Velocity Example, Head Movement Example, and MoveIt! Tutorial.

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/<side>/endpoint_state (baxter_core_msgs-EndpointState)

  • All of Pose, Twist, and Wrench measurements are reported with respect to the /base frame of the robot
  • 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 <side>_gripper tf frame. This frame is updated dynamically when grippers are connected to the robot or a Gripper Customization command is sent.
  • New in v1.0.0: 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!.

Inverse Kinematics Solver Service

The robot software provides a simple Position Inverse Kinematics (IK) Solver as a ROS Service. Specify a desired Cartesian coordinate and orientation for an Endpoint (in world x,y,z space), and the solver will return a set of joint angles that will get the arm there - or return an Invalid state if the pose is unreachable. An optional seed to start looking for solutions around can be specified as a joint angle configuration.

Note that the service takes an array of requests, and similarly returns an array of results with corresponding indexes. Similarly, optional seeds for each Endpoint request can be provided in a corresponding array of the same size as the requests array. This multiple array structure is a common structure used in ROS and explained in the sensor_msgs/JointState message.

SolvePositionIK Service [srv]
/ExternalTools/<side>/PositionKinematicsNode/IKService (baxter_core_msgs/SolvePositionIK.srv)

  • Request
    • pose_stamp (Required) - an array of geometry_msgs/PoseStamped requests, each defining the Cartesian <x,y,z> Position and Quaternion orientation of the Endpoint in the /base TF frame.
    • (Optional) seed_angles - an array of joint configuration seeds to start searching for solutions around, corresponding to each request in pose_stamp, where each individual seed is defined as a JointState message with the joint names and positions filled for all the arm Joints (so seed_angles is an array of arrays).
    • (Optional) seed_mode - specify the IK solver strategy for what types of seeds to use. By default (SEED_AUTO), the solver will iterate through the different strategies, starting with the user provided seed if it exists, until a solution is found. However, by explicitly setting the seed_mode to a specific mode, the solver will only return whether it was able to find a solution using that type of seed. The different mode types are defined as constants in the message (default: SEED_AUTO):
          uint8 SEED_AUTO    = 0
          uint8 SEED_USER    = 1
          uint8 SEED_CURRENT = 2
          uint8 SEED_NS_MAP  = 3
      
  • Response
    • result_type will be a corresponding array of uint8's, which will be 0 if no valid joint solution was found for the given Endpoint request; otherwise, it will be non-zero and correspond to the type of seed eventually used that gave a valid solution. These values correspond to the constants in the message used to specify seed_mode.
    • isValid will be a corresponding array of booleans which will be True if a valid joint solution was found for the given Endpoint request.
    • joints will contain joint solutions corresponding to each Endpoint request. Note that you should always check the result_type field to see if a valid joint solution was found, as invalid joint solutions can be returned in this array.

This service allows users to solve for basic IK joint angle solutions or perform workspace validation. The service will use a number of seeding strategies to find a solution. These strategies can be specified explicitly or just use the default to find the first solution in the possible methods. Optionally a Joint configuration can optionally be provided as a seed to the Solver.

Example:
# Seeded request call to the service
$ rosservice call /ExternalTools/left/PositionKinematicsNode/IKService "pose_stamp:
- header:
    seq: 0
    stamp: now
    frame_id: 'base'
  pose:
    position:
      x: 0.657579481614
      y: 0.851981417433
      z: 0.0388352386502
    orientation:
      x: -0.366894936773
      y: 0.885980397775
      z: 0.108155782462
      w: 0.262162481772
seed_angles:
- header: auto
  name: ['left_e0', 'left_e1', 'left_s0', 'left_s1', 'left_w0', 'left_w1', 'left_w2']
  position: [0.4371845240478516, 1.8419274289489747, 0.4981602602966309, -1.3483691110107423, -0.11850001572875977, 1.18768462366333, -0.002300971179199219]
seed_mode: 0"
# Returns:
joints: 
  - 
    header: 
      seq: 0
      stamp: 
        secs: 0
        nsecs: 0
      frame_id: ''
    name: ['left_s0', 'left_s1', 'left_e0', 'left_e1', 'left_w0', 'left_w1', 'left_w2']
    position: [0.015646076449046253, -0.5693474841530352, -0.022853580106295266, 1.2930237760722652, 0.05272603583796626, 0.27210782958564905, -0.03912130822108171]
    velocity: []
    effort: []
isValid: [True]
result_type: [1]

Head Joints

Head Position and State

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 or nodding. Note: Flags may not report 'true' values until after the first respective movement command is sent.

Component IDs:
head_nod, head_pan

Head State
/robot/head/head_state (baxter_core_msgs-HeadState)

  • pan field gives you the current angle (radians) of the head. 0 is forward, -pi/2 to Baxter's right, and +pi/2 to Baxter's left.
  • isPanning and isNodding are boolean fields 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. Note: The 'nod' joint will never update, as it is only a binary state.

Head Movement Control

Pan Head
/robot/head/command_head_pan (baxter_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.

Nod Head
/robot/head/command_head_nod (std_msgs-Bool)

  • Send True to nod!

Example:

    # Check head position/state: 
    $ rostopic echo /robot/head/head_state
    # Move (pan) head side-to-side: 
    $ rostopic pub /robot/head/command_head_pan baxter_core_msgs/HeadPanCommand -- 0.0 100
    # Make head nod up-down: 
    $ rostopic pub /robot/head/command_head_nod std_msgs/Bool True

Grippers (End-Effectors)

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, grippers 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 grippers, see the Gripper Example Program.

Gripper Configuration

Calibrate Gripper
/robot/end_effector/<side>_gripper/command (baxter_core_msgs-EndEffectorCommand)

  • Publish an End Effector Command message to calibrate a new gripper. 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
/robot/end_effector/<side>_gripper/command (baxter_core_msgs-EndEffectorCommand)

  • Publish a End Effector Command message to reset the gripper state.
  • The calibrated field of the gripper state message will reset to '0'.

Gripper State

Gripper State
/robot/end_effector/<side>_gripper/state (baxter_core_msgs-EndEffectorState)

  • The calibrated field must be true (1) before you can control the gripper. Use the command_calibrate topic 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
/robot/end_effector/<side>_gripper/state (baxter_core_msgs-EndEffectorState)

  • Publish a End Effector Command message to grip.

Simple Gripper Open
/robot/end_effector/<side>_gripper/state (baxter_core_msgs-EndEffectorState)

  • Publish a End Effector Command message to release.

Sensors

Accelerometers

Each 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, w0). The positive x-axis points towards the camera, and the y-axis points towards the cuff buttons, using standard Right-Hand-Rule notation.

Component IDs:
left_accelerometer, right_accelerometer

Read Linear Acceleration
/robot/accelerometer/<component_id>/state (sensor_msgs-Imu)

  • 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.
  • Note: linear_acceleration is currently the only valid data in the message. The sensor_msgs/Imu ROS message type is used for the sake of compatibility and standardization.

IR Range

There are two IR Range sensors on each hand. The sensor data is published on the tf frame <side>_hand_range, and points down the +x axis, as is convention for rviz.

Component IDs:
left_hand_range, right_hand_range

Read Range Sensor Measurements
/robot/range/<component_id> (sensor_msgs-Range)

  • Range is published in meters in the range field.
  • When the sensor goes beyond its max range, the invalid value of 65.5350036621(m) is published instead. Users should check for valid measurements using the min_range and max_range fields.

Sonar

Mounted in a ring around the head are 12 sonar distance sensors. There is also a yellow LED around each sensor that, by default, triggers when the corresponding sensor measures a distance below its threshold. For more information on controlling the lights on Baxter's head, see the Lights section.

Component IDs:
head_sonar

Read Sonar 3D Distances (Point Cloud)

The sonar range measurements are published as a set of 3D coordinate points in space around Baxter, called a PointCloud. This gives a "mapping" of detections in the workspace and is well-suited for occupancy-oriented reasoning in the robot's world.

Read Sonar Point Cloud
/robot/sonar/head_sonar/state (sensor_msgs-PointCloud)

  • The PointCloud message takes all the individual sonar range measurements and instead, uses the known locations of the sonar sensors on the robot, to map the readings into 'points' in 3D space that mark the location of detected objects.
  • The points for all incoming, valid, current readings are collected each time and published as an array in the PointCloud message.
  • Note: the result of this is that each published message contains measurements for only a subset of the sensors, not readings for all 12 sensors every time.
  • There will be a Point for each currently active measurement - this means a message published at one instant could contain points for only 4 of the sensors, and, also, another instant the published message could contain two points for the same sensor if the sensor had two valid measurements in the last time interval.
  • The points field contains the array of the actual 3D Points - one for each current measurement - in terms of the (x,y,z) coordinates for each point, relative to Baxter's base tf frame.
  • The channels field contains arrays with additional information about each point. The values in each array map 1:1 to the values at the same indices in the points array.
  • The array with the name SensorId lists which physical sensor each point came from.
  • The array with the name Distance lists the original range measurement from that sensor.

Inputs and Outputs

Navigators

There are four Navigators on Baxter's body: two on each side of the torso and one on each arm. Each Navigator is comprised of three push buttons, one of which is also an indexing scroll wheel, and two sets of blue LED lights.

Component IDs:
left_itb, right_itb, torso_left_itb, torso_right_itb

Navigator Input Buttons

Read Button States
/robot/navigators/<component_id>/state (baxter_core_msgs-ITBState)

  • The states of the three push buttons are the first three values in the boolean buttons[] array. A value of 'True' indicates the button is currently pushed down. The order is as follows:
  • OK_BUTTON (buttons[0]): The circular button in the middle of the Navigator.
  • CANCEL_BUTTON (buttons[1]): The button 'above' the OK_BUTTON, typically with a 'Back' arrow symbol.
  • SHOW_BUTTON (buttons[2]): The SHOW_BUTTON, or "Rethink Button", is 'below' the OK_BUTTON, and typically is labeled with the Rethink logo.

Read Wheel Index
/robot/navigators/<component_id>/state (baxter_core_msgs-ITBState)

  • The wheel 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.

Control Navigator Lights

There are two sets of lights on each Navigator: the 'inner' light ring around the circular OK Button, and the 'outer' oval light ring around the entire Navigator. Each light is identified by the 'Component ID' of its Navigator followed by _light_inner or _light_outer.

Component IDs:
Inner Lights: left_itb_light_inner, right_itb_light_inner, torso_left_itb_light_inner, torso_right_itb_light_inner
Outer Lights: left_itb_light_outer, right_itb_light_outer, torso_left_itb_light_outer, torso_right_itb_light_outer

Turn LEDs On/Off
/robot/digital_io/command (baxter_core_msgs-DigitalOutputCommand)

  • name: <navigator_component_id>_light_inner, <navigator_component_id>_light_outer
  • value: {True, False}
  • Publish a DigitalOutputCommand message with the component id of the light as the name and a value of True or False to turn the LEDs On or Off, respectively.

Check State of LEDs
/robot/digital_io/<light_component_id>/state (baxter_core_msgs-DigitalIOState)

  • The state field will give you the current setting of the LED, ON(1) or OFF(0).

Shoulder Buttons

There are two shoulder buttons on the back of the torso, one on each side. The state of each button is published in a DigitalIOState message under its own topic (DigitalIOState constants: PRESSED==1, UNPRESSED==0).

Component IDs:
left_shoulder_button, right_shoulder_button

Read Button Pressed
/robot/digital_io/<side>_shoulder_button/state (baxter_core_msgs-DigitalIOState)

  • The integer field state will read PRESSED (1) when the button is pressed down, and UNPRESSED (0) otherwise.

Cuff Buttons

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

Cuff (Squeeze) Sensor

Component IDs:
left_lower_cuff, right_lower_cuff

Read Cuff Squeezed
/robot/digital_io/<side>_lower_cuff/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the cuff sensor is squeezed, and UNPRESSED (0) otherwise.

Cuff OK Button

This is the circular button on the cuff.
Component IDs:
left_lower_button, right_lower_button

Read OK Button Pressed
/robot/digital_io/<side>_lower_button/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the button is pressed, and UNPRESSED (0) otherwise.

Cuff Grasp Button

This is the long, thin button on the cuff. Component IDs:
left_upper_button, right_upper_button

Read Grasp Button Pressed
/robot/digital_io/<side>_upper_button/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the button is pressed, and UNPRESSED (0) otherwise.

Lights

(Head) Halo LEDs

The 'Halo' light is the red/green light at the top of Baxter's head. The Halo is actually two separate lights - one for the red, one for the green - whose intensity levels can be independently controlled and mixed to produce a range of colors.

Control Light Brightness
/robot/sonar/lights/set_red_level (std_msgs-Float32)
/robot/sonar/lights/set_green_level (std_msgs-Float32)

  • Set the brightness level of the red or green light using a value between 0.0 (full off) and 100.0 (full on).

Read Current Light Levels
/robot/sonar/head_sonar/lights/red_level (std_msgs-Float32)
/robot/sonar/head_sonar/lights/green_level (std_msgs-Float32)

  • Brightness ranges from 0.0 (full off) to 100.0 (full on).

Sonar LED Indicators

The yellow LEDs surrounding each sonar sensor on the head default to automatically being turned on or off when something enters/leaves the respective sensor's range. This behavior can be overridden by publishing on the control topic below. The published value should be the bit-wise OR of the desired mode and state for the 12 individual LEDs. The two modes are Normal (sensor-based) operation, and Manual Override. See the definitions below. Note: Make sure you constantly publish the values at rate of at least 100Hz or the LEDs will timeout and revert to Normal operation.

To set the LEDs, pick one of the 'Mode's and OR it with any of the individual LED States desired:

   # Mode 
   DEFAULT_BEHAVIOR = 0x0000;
   OVERRIDE_ENABLE  = 0x8000;
   # States 
   ALL_LIGHTS_OFF   = 0x8000;
   ALL_LIGHTS_ON    = 0x0fff;
   LED_0_ON     0x0001
   LED_1_ON     0x0002
   LED_2_ON     0x0004
   LED_3_ON     0x0008
   LED_4_ON     0x0010
   LED_5_ON     0x0020
   LED_6_ON     0x0040
   LED_7_ON     0x0080
   LED_8_ON     0x0100
   LED_9_ON     0x0200
   LED_10_ON    0x0400
   LED_11_ON    0x0800
   LED_ALL_ON   0x8FFF
   LED_ALL_OFF  0x8000

Control Lights /robot/sonar/head_sonar/lights/set_lights (std_msgs-UInt16)

  • If bit 15 is zero, LEDs are controlled locally by Sonar.
  • Set bit 15 to enable overrides, bits 0-11 to control individual channel LEDs.
  • To use these flags, OR the OVERRIDE_ENABLE flag with the desired x_ON flags.

State of Lights /robot/sonar/head_sonar/lights/state (std_msgs-UInt16)

Navigator LEDs

(See: Navigator Lights)

Digital IO

Read Digital Input State
/robot/digital_io/<component_id>/state (baxter_core_msgs-DigitalIOState)

  • state: field will be 0 (for True, Pressed, On) or 1 (for False, Released, Off). If the component is an output, then the state field will be the current setting of the output.
  • isInputOnly: field tells you if the component is an input (sensor) only, and cannot output (not a light, actuator, nor indicator).

Control Digital Output /robot/digital_io/command (baxter_core_msgs-DigitalOutputCommand)

  • name: <component_id>
  • value: {True, False}
  • Publish a DigitalOutputCommand message with the component id of the Output as the name and a value of True or False to turn the Output On or Off, respectively.


All Digital Component IDs:
Outputs
Nav Inner Lights: left_itb_light_inner, right_itb_light_inner, torso_left_itb_light_inner, torso_right_itb_light_inner
Nav Outer Lights left_itb_light_outer, right_itb_light_outer, torso_left_itb_light_outer, torso_right_itb_light_outer
Configure Valves: left_blow, right_blow, left_suck, right_suck
Actuate Pneumatics: left_pneumatic, right_pneumatic
Camera Power: left_hand_camera_power, right_hand_camera_power, torso_camera_power
Inputs
(Analog) Raw IR Range Values: left_hand_range, right_hand_range
Back Shoulder Buttons: left_shoulder_button, right_shoulder_button
Cuff (Squeeze) Sensor: left_lower_cuff, right_lower_cuff
Cuff OK Button: left_lower_button, right_lower_button
Cuff Grasp Button: left_upper_button, right_upper_button
Safety Mat 'is attached': torso_process_sense0
Safety Mat 'is NOT actuated': torso_safety_stop

Pneumatics

Baxter is equipped with a pneumatic valve system that can be controlled independently on the left and right sides and fed to proper grippers for suction-based picking.   

Configure Valves

Blow Component IDs: left_blow, right_blow /robot/digital_io/<side>_blow/state (baxter_core_msgs-DigitalIOState)

  • Use to switch on/off the suck valve -- (does not activate suction).
  • Use this setting to grip objects in most cases.

Suck Component IDs: left_suck, right_suck /robot/digital_io/<side>_suck/state (baxter_core_msgs-DigitalIOState)

  • Use to switch off the blow valve -- (does not activate suction).
  • Use this setting to release objects in most cases.

Actuate Pneumatics

Turn On/Off Pneumatic Pressure/Airflow Component IDs: left_pneumatic, right_pneumatic /robot/digital_io/<side>_pneumatic/state (baxter_core_msgs-DigitalIOState)

  • This is how to use the pneumatic message.

Camera Power

Component IDs: left_hand_camera_power, right_hand_camera_power, torso_camera_power /robot/digital_io/<location>_camera_power/state (baxter_core_msgs-DigitalIOState)

Analog IO

(Analog) Input State /robot/analog_io/<component_id>/state (baxter_core_msgs-AnalogIOState)

  • value: is an integer often either rounded up from the hundreds decimal place or going from [0-100]

(Analog) Output Control /robot/analog_io/command ([1])

  • name: <component_id>
  • value: [0-65535] - (uint16)
  • Publish a AnalogOutputCommand message with the component id of the Output as the name and a uint16 value from [0-65535].


All Analog Component IDs
Outputs
Workspace Lights: torso_lighting
Torso Fan: torso_fan
Inputs
(Analog) Raw IR Range Values: left_hand_range, right_hand_range
Vacuum Sensor: left_vacuum_sensor_analog, right_vacuum_sensor_analog

Torso Fan

Component IDs: torso_fan Control Fan Speed /robot/analog_io/command (baxter_core_msgs-AnalogOutputCommand)

  • value: [0-100] power to the fan:
  • (0 = Auto, 1 = Off, 100 = Full-on)
  • Auto: Automatic control by hardware, based on torso board heatsink.

Fan State /robot/analog_io/torso_fan/state (baxter_core_msgs-AnalogIOState)

  • value: Current fan setting [0.0-100.0]

(Analog) Raw IR Range Values

Values are shifted by 3 decimal points (essentially in mm). Component IDs: left_hand_range, right_hand_range

Standard Integer Value /robot/analog_io/<side>_hand_range/value_uint32 (std_msgs-UInt32)
Analog Stamped State /robot/analog_io/<side>_hand_range/state (baxter_core_msgs-AnalogIOState)

Vacuum Sensor

Component IDs: left_vacuum_sensor_analog, right_vacuum_sensor_analog
Standard Integer Value /robot/analog_io/<side>_vacuum_sensor_analog/value_uint32 (std_msgs-UInt32)
Analog Stamped State /robot/analog_io/<side>_vacuum_sensor_analog/state (baxter_core_msgs-AnalogIOState)

Cameras

You can access Baxter's two hand cameras 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 Control Example and Using the Cameras for more information on using the cameras. Useful tools for using cameras in ROS include rviz and the image_view program. IMPORTANT: You can only have two cameras open at a time at standard resolutions, due to bandwidth limitations. The hand cameras are opened by default at boot-time,

Component IDs: left_hand_camera, right_hand_camera, head_camera

Camera Published Topics

Raw Image /cameras/<component_id>/image (sensor_msgs-Image)

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

Standardized Camera Intrinsics /cameras/<component_id>/camera_info_std (sensor_msgs-CameraInfo)

Camera Control Services

List Cameras Service_ [ _srv ] /cameras/list (baxter_core_msgs-ListCameras)

  • Call:
   $ rosservice call /cameras/list
  • Returns:
   cameras: ['<camera_name-1>', ... '<camera_name-n>']
  • Returns list of camera names.

Close Camera_ [ _srv ] /cameras/close (baxter_core_msgs-CloseCamera)

  • Call:
   $ rosservice call /cameras/close <camera_name>
  • Returns:
   err: <error_number> # 0, for success
  • Call this service with the <camera_name> argument set to the name of the camera to close (see List Cameras Service above).
  • Closes the specified camera.
  • If successful: Returns '0' in err field.
  • Else: Returns non-zero, integer error-code in err field.
    • From the command line, the camera name string can be given as an argument with or without quotes.

Open Camera_ [ _srv ] /cameras/open (baxter_core_msgs-OpenCamera)

  • Call:
   $ rosservice call /cameras/open '{name: <camera_name>, settings: {<optional settings>}}
  • Returns:
   err: <error_number> # 0, for success
  • Call this service with at least the name: field set to <camera_name> (see List Cameras Service above).
  • Opens the specified camera, with the optional settings parameters if given (see service type for more info on options).
  • If successful: Returns '0' in err field.
  • Else: Returns non-zero, integer error-code in err field.
    • From the command line, the camera name string can be given as an argument with or without quotes.
  • Currently available resolutions are: MODES = [(1280, 800); (960, 600); (640, 400); (480, 300); (384, 240); (320, 200)]
Example:
   # List available cameras
   $ rosservice call /cameras/list
   cameras: ['head_camera', 'left_hand_camera', 'right_hand_camera']
   # Close open camera
   $ rosservice call /cameras/close left_hand_camera
   err: 0
   # Open head camera with optional resolution
   $ rosservice call /cameras/open '{name: right_hand_camera, settings: {width: 960, height: 600 }}'
   err: 0
   # View now open camera topics
   $ rostopic list /cameras
   /cameras/head_camera/camera_info
   /cameras/head_camera/camera_info_std
   /cameras/head_camera/image
   /cameras/right_hand_camera/camera_info
   /cameras/right_hand_camera/camera_info_std
   /cameras/right_hand_camera/image

Screen (xdisplay)

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

Display Image /robot/xdisplay (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 Baxter's LCD screen, see the Display Image Example.

Simulator API

Baxter simulator API

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

Robot Movement Sensors+ I/O

Python Code API

For the baxter_interface Python classes (built on top of the ROS API), please see the Code API Reference page at: http://api.rethinkrobotics.com

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.

Tuck/Untuck Arms

A useful configuration for Baxter is the 'shipping pose' (the pose of Baxter's arms upon arrival). This configuration decscribes Baxter's arms tucked into a compact form for ease of movement through doorways etc. The easiest method for tucking/untucking the arms to/from the shipping pose is the example program 'tuck_arms.py' ROS executable:

Joints

Baxter has 7 joints (DoF) in each of its two arms and two more joints in its head (side-to-side panning, and binary, up-down nodding). The control for the head is done separately from the arms; however, you can read the current joint states (position, velocity, and effort) for all the joints on both arms 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).

The following sections cover the individual joint sensing and control in more detail:


Arm Joints

Component IDs:
left_e0, left_e1, left_s0, left_s1, left_w0, left_w1, left_w2, right_e0, right_e1, right_s0, right_s1, right_w0, right_w1, right_w2

Arm Joint States

/robot/joint_states (sensor_msgs-JointState)

  • name[i]: '<component_id>' of i-th joint in message value arrays.
  • position[i]: position of joint i rad
  • velocity[i]: velocity of joint i in rad/s
  • effort[i]: effort applied in joint i in Nm

Joint states are published by the robot_state_publisher and are updated with information from the sensors for every cycle.

Set Joint State Publishing Rate
/robot/joint_state_publish_rate (std_msgs-UInt16)

  • The rate at which the joints are published can be controlled by publishing a frequency on this topic.
  • Default rate is 100Hz; Maximum is 1000Hz.


Arm Joint Control

There are currently three modes for controlling the arms: Position Mode, Velocity Mode, and Torque Mode.

Alternatively, a joint trajectory action server has been created in support of timestamped joint position trajectories using the ROS standard joint trajectory action.

For more information on joint control, see the following movement example programs.

Joint Control Mode

Each arm can be in independent control modes by publishing the desired control mode to the topic for the appropriate arm.

Position Mode

The first is Position Mode, in which users publish target joint angles for given joints and the internal controller drives the arm to the published angles.

Velocity Mode

Warning: Advanced Control Mode. In Velocity Control Mode, users publish velocities for given joints and the joints will move at the specified velocity.

Torque Mode

Warning: Advanced Control Mode. In Torque Control Mode, users publish torques for given joints and the joints will move at the specified torque.

Switching Modes
/robot/limb/<side>/joint_command (baxter_core_msgs-JointCommand)

  • Mode is set implicitly by specifying the mode in the command message. Publish a JointCommand message to the joint_command topic for a given arm to set the arm into the desired control mode.
  • Constants for each mode are defined in the JointCommand message type.
Joint Trajectory Action

The Joint Trajectory Action provides an ROS action interface for tracking trajectory execution.

The joint trajectory action server provides an action interface for execution of trajectories requested by the client, known as a Goal* request. The joint trajectory action server then executes the request trajectory communicating the *Result response. The actionlib (action server/client interface) package differs from ROS services, simple request/response interface, in that actions allow mid-execution cancellation, they can also provide feedback during execution as to the progress of the Goal request.

Joint Trajectory Action Server
/robot/limb/<limb>/follow_joint_trajectory/cancel
/robot/limb/<limb>/follow_joint_trajectory/feedback
/robot/limb/<limb>/follow_joint_trajectory/goal
/robot/limb/<limb>/follow_joint_trajectory/result
/robot/limb/<limb>/follow_joint_trajectory/status

Usage:
# Verify that the robot is enabled:
$ rosrun baxter_tools enable_robot.py
# Start the joint trajectory action server:
$ rosrun baxter_interface joint_trajectory_action_server.py

Please see the simple joint trajectory example or joint trajectory playback example for examples of creating a client of this action server and requesting a joint trajectory.

Parameters:

The joint trajectory action server provides a number of parameters which describe it's behavior during the trajectory execution. These were largely designed to follow these standards.

Note: All of these parameters will be initialized on startup of the trajectory_controller.py if they were not previously specified. /rethink_rsdk_joint_trajectory_controller/<joint_name>__kp The proportional gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/<joint_name>__kd The derivative gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/<joint_name>__ki The integral gain with which the joint trajectory controller will track the commanded trajectory for the specified joint.

/rethink_rsdk_joint_trajectory_controller/goal_time (double, default: 0.0) The amount of time (in seconds) that the controller is permitted to be late to the goal. If goal_time has passed and the controller still has not reached the final position (within the parameters described by /rethink_rsdk_joint_trajectory_controller/<joint_name>_goal, then the goal is aborted.

/rethink_rsdk_joint_trajectory_controller/<joint>_goal (double, default: -1.0) The maximum final error for <joint> for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

/rethink_rsdk_joint_trajectory_controller/trajectory (double, default: -1.0) The maximum error for <joint> at any point during execution for the trajectory goal to be considered successful. Negative numbers indicate that there is no constraint. Given in units of joint position (radians). If this constraint is violated, the goal is aborted.

Dynamic Reconfigure GUI is suggest for use with ROS Distributions >=Groovy for setting these parameters.

# Start the dynamic reconfigure GUI:
$ rosrun rqt_reconfigure rqt_reconfigure

Expand the joint trajectory controller's parameters by choosing rethink_rsdk_joint_trajectory_controller from the left menu. Use the sliders/input fields to specify these parameters dynamically.

Alternatively, these parameters can be set via a YAML file, command line, or programmatically (rospy, roscpp).

For additional information on joint control, see the Joint Position Example, Joint Velocity Example, Head Movement Example, and MoveIt! Tutorial.

Head Joints

Head Position and State

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 or nodding. Note: Flags may not report 'true' values until after the first respective movement command is sent. Even though the head nodding cannot be visualized in gazebo, the head state topic would indicate if the command is passed

Component IDs:
head_nod, head_pan

Head State
/robot/head/head_state (baxter_core_msgs-HeadState)

  • pan field gives you the current angle (radians) of the head. 0 is forward, -pi/2 to Baxter's right, and +pi/2 to Baxter's left.
  • isPanning and isNodding are boolean fields 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. Note: The 'nod' joint will never update, as it is only a binary state.

Head Movement Control

Pan Head
/robot/head/command_head_pan (baxter_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.Note: Speed of the head movement cannot be controlled at this point of time.

Nod Head
/robot/head/command_head_nod (std_msgs-Bool)

  • Send True to nod!

Example:

# Check head position/state: 
$ rostopic echo /robot/head/head_state
# Move (pan) head side-to-side: 
$ rostopic pub /robot/head/command_head_pan baxter_core_msgs/HeadPanCommand -- 10.0 100
# Make head nod up-down: 
$ rostopic pub /robot/head/command_head_nod std_msgs/Bool True

Cartesian (Endpoint State)

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/<side>/endpoint_state (baxter_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.Note: The wrench and the twist values would be 0 for the simulated baxter since it is not implemented.

Sensors

Accelerometers

Each 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, w0). The positive x-axis points towards the camera, and the y-axis points towards the cuff buttons, using standard Right-Hand-Rule notation.

Component IDs:
left_accelerometer, right_accelerometer

Read Linear Acceleration
/robot/accelerometer/<component_id>/state (sensor_msgs-Imu)

  • 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.
  • Note: linear_acceleration is currently the only valid data in the message. The sensor_msgs/Imu ROS message type is used for the sake of compatibility and standardization.

IR Range

There are two IR Range sensors on each hand. The sensor data is published on the tf frame <side>_hand_range, and points down the +x axis, as is convention for rviz.

Component IDs:
left_hand_range, right_hand_range

Read Range Sensor Measurements
/robot/range/<component_id> (sensor_msgs-Range)

  • Range is published in meters in the range field.
  • When the sensor goes beyond its max range, the invalid value of 65.5350036621(m) is published instead. Users should check for valid measurements using the min_range and max_range fields.

Sonar

Mounted in a ring around the head are 12 sonar distance sensors.

Component IDs:
head_sonar

Read Sonar 3D Distances (Point Cloud)

The sonar range measurements are published as a set of 3D coordinate points in space around Baxter, called a PointCloud. This gives a "mapping" of detections in the workspace and is well-suited for occupancy-oriented reasoning in the robot's world.

Read Sonar Point Cloud
/robot/sonar/head_sonar/state (sensor_msgs-PointCloud)

  • The PointCloud message takes all the individual sonar range measurements and instead, uses the known locations of the sonar sensors on the robot, to map the readings into 'points' in 3D space that mark the location of detected objects.
  • The points for all incoming, valid, current readings are collected each time and published as an array in the PointCloud message.
  • Note: the result of this is that each published message contains measurements for only a subset of the sensors, not readings for all 12 sensors every time.
  • There will be a Point for each currently active measurement - this means a message published at one instant could contain points for only 4 of the sensors, and, also, another instant the published message could contain two points for the same sensor if the sensor had two valid measurements in the last time interval.
  • The points field contains the array of the actual 3D Points - one for each current measurement - in terms of the (x,y,z) coordinates for each point, relative to Baxter's base tf frame.
  • The channels field contains arrays with additional information about each point. The values in each array map 1:1 to the values at the same indices in the points array.
  • The array with the name SensorId lists which physical sensor each point came from.
  • The array with the name Distance lists the original range measurement from that sensor.

Inputs and Outputs

Navigators

There are four Navigators on that are simulated as a QT plugin in the simulated baxter: two for each side of the torso and one for each arm. Each Navigator is comprised of three push buttons, and an indexing scroll wheel.

Component IDs:
left_navigator, right_navigator, torso_left_navigator, torso_right_navigator

Navigator Input Buttons

Read Button States
/robot/navigators/<component_id>/state (baxter_core_msgs-ITBState)

  • The states of the three push buttons are the first three values in the boolean buttons[] array. A value of 'True' indicates the button is currently pushed down. The order is as follows:
  • OK_BUTTON (buttons[0]): The small rectangular button labelled as 'Ok'.
  • CANCEL_BUTTON (buttons[1]): The button 'above' the OK_BUTTON, labelled as 'Cancel'.
  • SHOW_BUTTON (buttons[2]): The SHOW_BUTTON, or "Rethink Button", is 'below' the OK_BUTTON, and typically is labeled as the 'Show'.

Read Wheel Index
/robot/navigators/<component_id>/state (baxter_core_msgs-ITBState)

  • The wheel 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.

Control Navigator Lights

There are two sets of lights on each Navigator: the 'inner' light ring around the circular OK Button, and the 'outer' oval light ring around the entire Navigator. Each light is identified by the 'Component ID' of its Navigator followed by _light_inner or _light_outer.

Component IDs:
Inner Lights: left_inner_light, right_inner_light, torso_left_inner_light, torso_right_inner_light
Outer Lights: left_outer_light, right_outer_light, torso_left_outer_light, torso_right_outer_light

Turn LEDs On/Off
/robot/digital_io/command (baxter_core_msgs-DigitalOutputCommand)

  • name: <navigator_component_id>_light_inner, <navigator_component_id>_light_outer
  • value: {True, False}
  • Publish a DigitalOutputCommand message with the component id of the light as the name and a value of True or False to turn the LEDs On or Off, respectively.

Check State of LEDs
/robot/digital_io/<light_component_id>/state (baxter_core_msgs-DigitalIOState)

  • The state field will give you the current setting of the LED, ON(1) or OFF(0).Note: The Navigator LED are not simulated in gazebo and hence viewing the lights go on and off is not possible. However, the topics mentioned above indicate the appropriate states of these lights.

Shoulder Buttons

There are two shoulder buttons on the back of the torso, one on each side. The state of each button is published in a DigitalIOState message under its own topic (DigitalIOState constants: PRESSED==1, UNPRESSED==0).

Component IDs:
left_shoulder_button, right_shoulder_button

Read Button Pressed
/robot/digital_io/<side>_shoulder_button/state (baxter_core_msgs-DigitalIOState)

  • The integer field state will read PRESSED (1) when the button is pressed down, and UNPRESSED (0) otherwise.

Cuff Buttons

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

Cuff (Squeeze) Sensor

Component IDs:
left_lower_cuff, right_lower_cuff

Read Cuff Squeezed
/robot/digital_io/<side>_lower_cuff/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the cuff sensor is squeezed, and UNPRESSED (0) otherwise.

Cuff OK Button

This is the circular button on the cuff.
Component IDs:
left_lower_button, right_lower_button

Read OK Button Pressed
/robot/digital_io/<side>_lower_button/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the button is pressed, and UNPRESSED (0) otherwise.

Cuff Grasp Button

This is the long, thin button on the cuff. Component IDs:
left_upper_button, right_upper_button

Read Grasp Button Pressed
/robot/digital_io/<side>_upper_button/state (baxter_core_msgs-DigitalIOState)

  • Integer state will read PRESSED (1) when the button is pressed, and UNPRESSED (0) otherwise.

Lights

Digital IO

Read Digital Input State
/robot/digital_io/<component_id>/state (baxter_core_msgs-DigitalIOState)

  • state: field will be 0 (for True, Pressed, On) or 1 (for False, Released, Off). If the component is an output, then the state field will be the current setting of the output.
  • isInputOnly: field tells you if the component is an input (sensor) only, and cannot output (not a light, actuator, nor indicator).

Control Digital Output /robot/digital_io/command (baxter_core_msgs-DigitalOutputCommand)

  • name: <component_id>
  • value: {True, False}
  • Publish a DigitalOutputCommand message with the component id of the Output as the name and a value of True or False to turn the Output On or Off, respectively.

All Digital Component IDs:
Outputs:
Inner Lights: left_inner_light, right_inner_light, torso_left_inner_light, torso_right_inner_light
Outer Lights: left_outer_light, right_outer_light, torso_left_outer_light, torso_right_outer_light

Inputs:
Back Shoulder Buttons: left_shoulder_button, right_shoulder_button
Cuff (Squeeze) Sensor: left_lower_cuff, right_lower_cuff
Cuff OK Button: left_lower_button, right_lower_button
Cuff Grasp Button: left_upper_button, right_upper_button Note: The /robot/digital_io_states is not yet simulated to publish compiled states of the digital_io and the individual state topic of each of the navigator would furnish those information

Cameras

You can access Baxter's two hand cameras and the head camera using the standard ROS image types and image_transport mechanism listed below. These cameras would show rendered images of the gazebo environment. Useful tools for using cameras in ROS include rviz and the image_view program. IMPORTANT: There is no limitation on the number of cameras used simultaneously in simulation as in the real baxter.

Component IDs: left_hand_camera, right_hand_camera, head_camera

Camera Published Topics

Raw Image /cameras/<component_id>/image (sensor_msgs-Image)

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

 
# View now open camera topics
$ rostopic list /cameras
  /cameras/head_camera/camera_info
  /cameras/head_camera/image
  /cameras/right_hand_camera/camera_info
  /cameras/right_hand_camera/image
  /cameras/left_hand_camera/camera_info
  /cameras/left_hand_camera/image

Screen (xdisplay)

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

Display Image /robot/xdisplay (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 Baxter's LCD screen, see the Display Image Example. For more information on the working of each example with the simulator refer here


<headertabs />