Arm Control Modes

From sdk-wiki
Jump to: navigation, search

Control Modes

Fundamental to the operation of Baxter via the SDK is a familiarity with the available joint control modes. The joint control modes define the 'modes' in which we can control Baxter's limbs in joint space. These are provided via a ROS message API:(baxter_core_msgs/JointCommand.msg)

To control the limb, we must publish the JointCommand message on the topic:

robot/limb/<left/right>/joint_command

at a rate > 5hz (by default). The rate at which you must publish your messages is defined on the topic:

/robot/limb/<left/right>/joint_command_timeout

of message type std_msgs/Float64

Message Definition

The JointCommand message is defined:

int32 mode
float64[] command
string[]  names

int32 POSITION_MODE=1
int32 VELOCITY_MODE=2
int32 TORQUE_MODE=3
int32 RAW_POSITION_MODE=4

This message is subscribed to by the realtime_loop.

mode: The mode is an integer defining the mode in which the commands will be parsed and commanded to the Joint Controller Boards (JCBs). Available modes are contained with the message [POSITION_MODE, VELOCITY_MODE, TORQUE_MODE,RAW_POSITION_MODE]

command: The command is the ordered (corresponding to the names field) command values.

names: The names is a list of strings containing the joints to command.

Joint Control Fundamentals

When a joint position command is published from the development PC, the 'realtime_loop' process which represents a motor control plugin subscribes to this message. This message is then parsed, and represented in memory based on control mode.

Depending on the control mode, modifications are made to the input commands. These modifications are typically due to the safety controllers (e.g. arm-to-arm collision avoidance, collision detection, etc.)

A control rate timeout is also enforced at this motor controller layer. This states that if a new 'JointCommand' message is not received within the specified timeout (0.2 seconds, or 5Hz), the robot will 'Timeout'. When the robot 'Times out', the current control mode is exited, reverting back to position control mode where the robot will command (hold) it's current joint angles. The reason for this is safety. For example, if controlling in velocity control mode where you are commanding 1.0 Rad/s to joint S0, and you lose network connectivity (someone kicks your router), the robot could result in dangerous motions. By 'timing out', the robot will be safer, reacting to network timeouts, or incorrect control behavior.

This control rate timeout is configurable:

/robot/limb/<left/right>/joint_command_timeout

of message type std_msgs/Float64

Joint Position Control

Joint position control mode is the fundamental, basic control mode for Baxter arm motion. In position control mode, we specify joint angles at which we want the joints to achieve. Typically this will be consist of seven values, a commanded position for each of the seven joints, resulting in a full description of the arm configuration.

JointCommand.msg mode: POSITION_MODE

This joint command is then subscribed to by Baxter's Motor Controller. The motor controller processes this joint command ensuring safety (collision avoidance and detection) and expected behavior by making the following modifications:

Joint Position Control.png

"Raw" Joint Position Control

Raw Joint position control mode was introduced to provide a much more direct position control method. The same basic idea as the standard joint position control mode still holds. However, the joint commands are largely left to the JCBs for execution.

JointCommand.msg mode: RAW_POSITION_MODE

The 'raw' joint position commands only perform the following modification (typically these additions are none):

'Raw' Joint Position Control.png

Warning: Advanced Control Mode. As we no longer apply collision avoidance offsets, and allow for very fast motions at the joints velocity limits, this mode can be dangerous. Please use with caution.

Joint Velocity Control

Joint velocity control mode is an advanced control mode. In velocity control mode, we specify joint velocities at which we want the joints to simultaneously achieve. Typically this will be consist of seven values, a commanded velocity for each of the seven joints.

JointCommand.msg mode: VELOCITY_MODE

This joint command is then subscribed to by Baxter's Motor Controller. The motor controller processes this joint velocity command (applying collision avoidance and detection) and expected behavior by making the following modifications:

Joint Velocity Control.png

Note: When commanding joint velocities, if a commanded velocity to one of the joints will result in a joint position that is beyond the joints limits, no joints will be commanded, as all of the command is considered invalid. Reason we do this; an example of a common control method, using the Jacobian for Cartesian control resulting in joint velocity commands. If a single joint hits its limit, the rest of the joints will still be commanded, resulting in obscure and potentially dangerous motions. We recommend either implementing a joint space potential field or joint limit check before submitting the joint velocity commands.

Warning: Advanced Control Mode. As we allow for very fast joint velocity up to the joint velocity limits, this mode can be dangerous. Please use with caution.

Joint Torque Control

Joint torque control mode is an advanced control mode. In torque control mode, we specify joint torques at which we want the joints to simultaneously achieve. Typically this will be consist of seven values, a commanded torque for each of the seven joints.

JointCommand.msg mode: TORQUE_MODE

This joint command is then subscribed to by Baxter's Motor Controller. The motor controller processes this joint torque command and expected behavior by making the following modifications, taking special note of the absence of collision avoidance and detection modules:

Joint Torque Control.png

Note: As shown in the above image, joint torque commands are applied in addition to gravity and spring compensation torques. This default can be disabled by publishing an std_msgs/Empty message on the topic: /robot/limb/right/suppress_gravity_compensation at a rate > 5Hz.

Warning: Advanced Control Mode. When commanding in torque control mode, access is granted to the lowest control levels. This puts much responsibility on the control program and can be dangerous. Please use with caution.