Arm Control Systems

Revision as of 20:12, 21 November 2017 by Andypark (talk | contribs) (Undo revision 1339 by Andypark (talk))
Jump to: navigation , search

Control Overview

Joint Command Overview

Sawyer's arm controls flows through on four layers of operation:

1) User Code running via workstation (Python Joint Control or Joint Trajectory Action Server or your custom interface)
2) Joint Control Listeners via ROS topic (on Sawyer's internal Ubuntu Linux PC)
3) RealTime Motor Control Loop (the highest priority process on Sawyer's internal Ubuntu Linux PC)
4) Joint Control Boards (microcontrollers attached to each arm joint)

The bottom three layers (2-4) are not accessible for user modification because they run on the robot itself and its microcontrollers. Sawyer does have three joint control modes for the user to choose from at the top level: position, velocity, and torque control. Each controller has a subset of Motor Controller Plugins associated with them. By default, all the joint control publishers and subscribers provided by the Sawyer SDK run at 100Hz, but can be run up to a rate of 800Hz reliably. See the links for more detailed explanations.

Joint Command Timing

Start to finish, a joint is commanded from the user's python code. This message flows over the ROS network and is picked up by the Joint Control Listeners which store the command for it to be retrieved asynchronously by the RealTime Motor Control Loop once per 1ms (1KHz). The command is then sent to the Joint Control Boards (JCB) and executed within the same 1ms timeslot. On the next 1ms cycle, the joint position and spring deflection sensor are read and transferred back to the Joint Control Publisher. The result is read over the ROS network by the user's code. The total timing looks approximately as follows:

1.6ms for the Command to publish over ROS to the Joint Controller over rostopic (via network)
1ms for the Joint Controller Listener to command the Motor Controller (MC), running an async real time loop of 1KHz
1ms for the MC to transfer to the Joint Control Board (JCB) and evaluate the command
1ms for the JCB to read the updated status and give a response to the MC
1ms for the MC to report back to the Joint Controller Publisher
1.6ms for the Joint Controller to publishing the State back over rostopic (via network)
________
~ 7.2ms total round trip ROS User Publisher to ROS user Subscriber


RealTime Motor Controller

The RealTime Motor Control loop on the robot executes over the course of 1ms, and approximately 700us of this loop is used on average. Occasionally you may find an overrun of the RealTime loop around 100us. This overrun usually does not propagate forward to other cycles because the next loop will likely take 700us. To verify this you can look at the diagnostics messages via "rostopic echo /diagnostics", and look for the "Realtime Control Loop".

The RealTime Motor Controller has plugins that run simultaneously with joint commands. These are Collision Avoidance and Detection, Gravity Compensation and Spring Hysteresis/Crosstalk Compensation. On top of these plugins, when Sawyer's cuff pressure sensor is activated, Zero-G Mode enables, allowing the arm to be passively back driven. Upon releasing the cuff, the motor controller returns to the controller it was using previously.

Interaction Control Mode

Interaction control mode is an advanced control mode. In interaction control mode, either impedance control or force control is performed at the endpoint. Also, having 7 joints in Sawyer arm allows movements in the arm without affecting the endpoint pose, which corresponds to nullspace motion. So, independently of the control at the endpoint, stiffness control can be performed as well in the nullspace. The following figure illustrates the interaction control at the endpoint as well as the nullspace.

Impedance Control Concept Sketch.png


Impedance Control Concept

In general, impedance control models the dynamic behavior of the endpoint of the arm as a mass-spring-damper system. In interaction control for Sawyer, the endpoint of the arm is modeled as a spring-damper system as

ImpedanceControlEquationRevised1.png

Additionally, nullspace stiffness control torques can be computed as

ImpedanceControlEquationRevised2.png

Using the above equation, in each of 6 Cartesian axes, desired interaction force can be computed from desired and actual endpoint velocities and positions (and orientations). The computed force can then be used to compute desired joint torques as

ImpedanceControlEquationRevised3.png

It can be noted that the magnitude of this impedance force linearly increases as the actual position goes away from the desired one, which means that if the end-effector is blocked somehow, then the applied force could become very large. This can be dangerous and lead to breakage of the parts or environment. To prevent this, we provide IMPEDANCE_WITH_FORCE_LIMIT_MODE which limits the impedance force to a specified limit, and the applied force during interaction can be ensured to be below the limit.

Note that for rotational stiffness control, a similiar control law is constructed based on the orientation error represented by quaternions. By default, the maximum amount of orientation error is limited by a virtual wall, but this limit can be disabled by setting rotations_for_constrained_zeroG to True.


Force Control Concept

In force control, the desired force can be specified in each of Cartesian axes. The units are [N] and [Nm] for the first three translational directions and the last three rotational directions, respectively.

Force control is supposed to be used only during contact since applying force in free space would generate acceleration at the endpoint, which can be very dangerous. So for safety reasons a damping control force is added by default to limit the velocity during the force control, and it can be disabled by setting disable_damping_in_force_control to True.

Also, the force control does not have notion of limits to range of motion, which means that the end-effector will move as long as the joints do not reach their limits if force control is done only in free space. If it is desired to limit the amount of changes in position and orientation during force control, FORCE_WITH_MOTION_LIMIT_MODE can be used. Note that this mode is experimental at this point, and the SDK interface provides no parameters to specify its motion limits. Currently the limits are set to 0.12[m] and 0.2618[rad].


Interaction Control Overview

In interaction control mode, the user can specify interaction parameters along with joint angles from which the endpoint pose is computed. These inputs are then subscribed to by Sawyer's Interaction Controller. The interaction controller processes these inputs and generate interaction torques ensuring safety (collision avoidance and detection) and expected behavior by making the following modifications:

Diagram Interaction Controller Revised.png


Interaction Control Command

In order to use interaction control mode, we must publish the InteractionControlCommand message on the topic:

/robot/limb/right/interaction_control_command

Message Definition

The Interaction Control Command message is defined:

# Message sets the interaction (impedance/force) control on or off
# It also contains desired cartesian stiffness K, damping D, and force values

Header header
bool      interaction_control_active

## Mode Selection Parameters
# The possible interaction control modes are:
# Impedance mode: implements desired endpoint stiffness and damping.
uint8 IMPEDANCE_MODE=1
# Force mode: applies force/torque in the specified dimensions.
uint8 FORCE_MODE=2
# Impedance with force limit: impedance control while ensuring the commanded
# forces/torques do not exceed force_command.
uint8 IMPEDANCE_WITH_FORCE_LIMIT_MODE=3
# Force with motion bounds: force control while ensuring the current
# pose/velocities do not exceed forceMotionThreshold (currenetly defined in yaml)
uint8 FORCE_WITH_MOTION_LIMIT_MODE=4

# Specifies the interaction control mode for each Cartesian dimension (6)
uint8[] interaction_control_mode

# All 6 values in force and impedance parameter vectors have to be filled,
# If a control mode is not used in a Cartesian dimension,
# the corresponding parameters will be ignored.

## Cartesian Impedance Control Parameters
# Stiffness units are (N/m) for first 3 and (Nm/rad) for second 3 values
float64[] K_impedance
# Force certain directions to have maximum possible impedance for a given pose
bool[] max_impedance
# Damping units are (Ns/m) for first 3 and (Nms/rad) for the second 3 values
float64[] D_impedance
# Joint Nullspace stiffness units are in (Nm/rad) (length == number of joints)
float64[] K_nullspace

## Parameters for force control or impedance control with force limit
# If in force mode, this is the vector of desired forces/torques
# to be regulated in (N) and (Nm)
# If in impedance with force limit mode, this vector specifies the
# magnitude of forces/torques (N and Nm) that the command will not exceed.
float64[] force_command

## Desired frame
geometry_msgs/Pose interaction_frame
string endpoint_name
# True if impedance and force commands are defined in endpoint frame
bool in_endpoint_frame

# Set to true to disable damping during force control. Damping is used
# to slow down robot motion during force control in free space.
# Option included for SDK users to disable damping in force control
bool disable_damping_in_force_control

# Set to true to disable reference resetting. Reference resetting is
# used when interaction parameters change, in order to avoid jumps/jerks.
# Option included for SDK users to disable reference resetting if the
# intention is to change interaction parameters.
bool disable_reference_resetting

## Parameters for Constrained Zero-G Behaviors
# Allow for arbitrary rotational displacements from the current orientation
# for constrained zero-G. Setting 'rotations_for_constrained_zeroG = True'
# will disable the rotational stiffness field which limits rotational
# displacements to +/- 82.5 degree.
# NOTE: it will be only enabled for a stationary reference orientation
bool rotations_for_constrained_zeroG

This message is subscribed to by the realtime_loop.

interaction_control_active: The interaction_control_active is a boolean to activate (True) or deactivate (False) interaction control mode. When it is set to False, the arm is put in position mode.

interaction_control_mode: The interaction_control_mode is an integer defining the internal mode in interaction control mode. Available modes are contained with the message [IMPEDANCE_MODE, FORCE_MODE, IMPEDANCE_WITH_FORCE_LIMIT_MODE, FORCE_WITH_MOTION_LIMIT_MODE]

K_impedance: The K_impedance is a list of desired stiffness values for 6 Cartesian axes (translational directions along x, y, and z axes followed by rotational directions about x, y, and z axes of the reference frame). Each of them must be equal or greater than 0, and they will be capped to their maximum values (1300 [N/m] and 30 [Nm/rad], respectively) if exceeded.

max_impedance: The max_impedance is a list of booleans for 6 Cartesian axes. For directions whose values are set to True, a maximum stiffness value will be computed for the current joint configuration, and will be used regardless of the values of K_impedance. The maximum stiffness values are somewhere between 1300 [N/m] and 3000 [N/m] and 30 [Nm/rad]] and 300 [Nm/rad] for translational and rotational directions, respectively.

D_impedance: The D_impedance is a list of desired damping values for 6 Cartesian axes. If unspecified, default values are used, which are scaled according to stiffness values. The default damping values are 8 [Ns/m] and 2 [Nms/rad] for tranlational and rotational directions, respectively.

K_nullspace: The K_nullspace is a list of desired nullspace stiffness values for all 7 joints. Each of them must be equal or greater than 0, and they will be capped to their maximum values (10 [Nm/rad]) if exceeded.

force_command: The force_command is a list of desired force values for 6 Cartesian axes. Each of them will be capped to their maximum values (50 [N] and 5 [Nm] for translational and rotational directions, respectively) if exceeded.

interaction_frame: The interaction_frame is a geometry_msgs/Pose that specifies the position and orientation of the reference frame with respect to which the interaction control behaviors are defined.

endpoint_name: The endpoint_name is a string that specifies the name of the endpoint frame at which the interaction control behaviors are defined. Note that currently this field is not allowed to be modified, and it is always set to right_hand by default.

in_endpoint_frame: The in_endpoint_frame is a boolean, which can be used to set the endpoint frame (i.e., TCP frame) as the reference frame of interaction control behaviors if set to True; Base frame will be used if set to False.

disable_reference_resetting: The disable_reference_resetting is a boolean. To avoid jumps/jerks in the event of a change in interaction parameters, the interaction controller resets the reference position to the actual position. This feature can be disabled by setting the variable disable_reference_resetting to True.

Motion Controller Interface

The motion controller interface allows the SDK to access the built-in trajectory generation and motion control features in Sawyer. It provides a set of classes that are used to construct an intera_motion_msgs/Trajectory message, as well as an action server that will pass that message along to the motion controller. The motion controller will then generate and run a motion plan from that trajectory message.

Trajectory Message

A intera_motion_msgs/Trajectory message is used to specify a trajectory for Sawyer. It contains a sequence of waypoints that the trajectory should pass through, as well as the interpolation type, kinematic constraints, and interaction parameters. Generally the trajectory message is created using the MotionTrajectory class, but advanced users might choose to create it directly. A trajectory message can be sent to the motion controller using either the MotionTrajectory class (prefered method) or the MotionControllerActionClient class (advanced users).

Motion Trajectory

The MotionTrajectory class is used as a utility to create and send intera_motion_msgs/Trajectory messages. The simplest way to use it is to call the append_waypoint() to build up a sequence of waypoints and then call send_trajectory() to plan and execute the a trajectory that passes through the waypoints. The MotionWaypoint, MotionWaypointOptions, and InteractionOptions classes are all utilities that help with the construction of trajectories.

Motion Waypoint

The MotionWaypoint class is used as utility to create intera_motion_msgs/Waypoint messages. It can be directly passed to the append_waypoint() method of a MotionTrajectory, or you can use the to_msg() method to directly use the ROS message format. All unspecified parameters are set to reasonable default values.

Motion Waypoint Options

The MotionWaypointOptions class is used as utility to create intera_motion_msgs/WaypointOptions messages. A MotionWaypointOptions object can be passed to MotionWaypoint.set_waypoint_options(), or you can use the to_msg() method to directly use the ROS message format. All unspecified parameters are set to reasonable default values.

Interaction Options

The InteractionOptions class is used as a utility to create intera_core_msgs/InteractionControlCommand messages. Use the to_msg() method to extract the ROS message for use in populating an intera_motion_msgs/TrajectoryOptions message. All unspecified parameters are set to reasonable default values.

Interaction Control Mode

Interaction control mode is an advanced control mode. In interaction control mode, either impedance control or force control is performed at the endpoint. Also, having 7 joints in Sawyer arm allows movements in the arm without affecting the endpoint pose, which corresponds to nullspace motion. So, independently of the control at the endpoint, stiffness control can be performed as well in the nullspace. The following figure illustrates the interaction control at the endpoint as well as the nullspace.

Impedance Control Concept Sketch.png

Impedance Control Concept

In general, impedance control models the dynamic behavior of the endpoint of the arm as a mass-spring-damper system. In interaction control for Sawyer, the endpoint of the arm is modeled as a spring-damper system as

ImpedanceControlEquationRevised1.png

Additionally, nullspace stiffness control torques can be computed as

ImpedanceControlEquationRevised2.png

Using the above equation, in each of 6 Cartesian axes, desired interaction force can be computed from desired and actual endpoint velocities and positions (and orientations). The computed force can then be used to compute desired joint torques as

ImpedanceControlEquationRevised3.png

It can be noted that the magnitude of this impedance force linearly increases as the actual position goes away from the desired one, which means that if the end-effector is blocked somehow, then the applied force could become very large. This can be dangerous and lead to breakage of the parts or environment. To prevent this, we provide another mode (impedance with force limit) which limits the impedance force to a specified limit, and the applied force during interaction can be ensured to be below the limit.

Note that for rotational stiffness control, a similiar control law is constructed based on the orientation error represented by quaternions. By default, the maximum amount of orientation error is limited by a virtual wall, but this limit can be disabled by setting rotations_for_constrained_zeroG to True.

Force Control Concept

In force control, the desired force can be specified in each of Cartesian axes. The units are [N] and [Nm] for the first three translational directions and the last three rotational directions, respectively.

Force control is supposed to be used only during contact since applying force in free space would generate acceleration at the endpoint, which can be very dangerous. So for safety reasons a damping control force is added by default to limit the velocity during the force control, and it can be disabled by setting disable_damping_in_force_control to True.

Also, the force control does not have notion of limits to range of motion, which means that the end-effector will move as long as the joints do not reach their limits if force control is done only in free space. If it is desired to limit the amount of changes in position and orientation during force control, the forth mode of force control with motion limits can be used. Note that this mode is experimental at this point, and the SDK interface provides no parameters to specify its motion limits. Currently the limits are set to 0.12[m] and 0.2618[rad].

Joint Trajectory Action Server

Sawyer's SDK comes equipped with Joint Trajectory Action Server (JTAS) to facilitate users needing to command either (or both) of Sawyer's arm through multiple waypoints. These waypoints are supplied as positions, velocities, and/or accelerations for every joint in Sawyer's arm. These waypoints are accompanied by a desired timeframe within which the trajectory must complete. The main benefit of this server is its ability to interpolate between supplied waypoints, command Sawyer's joints accordingly, and ensure the trajectory is being followed within a specified tolerance. To read more about JTA Servers in general, please see the ROS Wiki page on Joint Trajectory Action. To jump straight to the source code, see the intera_interface JTAS page on GitHub.

JTAS Modes

The JTAS has three modes: Velocity, Position, and Feed Forward Position Mode, 'position', 'velocity' Position, which are invoked as arguments when calling the action server:
$ rosrun intera_interface joint_trajectory_action_server.py

  • Velocity Mode (--mode velocity)
  • Position Mode (--mode position)
  • Inverse Dynamics Feed Forward Position Mode (default mode)

Velocity Mode

This mode executes direct control of trajectories by calculating and commanding the velocities required to move the arm through a set of joint positions at a specified time. The end result is fast, but less accurate movement.

Position Mode

This mode allows for simple trajectory execution of position-only trajectories. This mode is significantly more accurate than velocity mode, at a cost of a speed reduction.

Inverse Dynamics Feed Forward Position Mode (using Join Trajectory Position Mode)

This mode can allow for the highest speed movement with the most accuracy. By supplying desired Positions, Velocities, and Accelerations for each joint, you give Sawyer to anticipate and correct for the dynamics of its movement by "feeding forward" Velocities and Accelerations to the Motor Controller. This enables Sawyer to use both feedback from its spring deflection sensors, and feed forward from dynamics of the anticipated trajectory to accurately execute trajectories.

This mode accepts trajectories with Position, Velocity, and/or Acceleration supplied for each joint. Position is required, but Velocity and Acceleration are optional. Supplying Position alone will give you movement very similar to regular Position mode. If the optional Velocities and Accelerations are supplied, they are splined together with Position, and then commanded over the /robot/inverse_dynamics topic. MoveIt! supplies these three dimensions by default, so it is highly recommended that you use this mode when using that motion planner.

Collision Model

There are a total of three levels of collision models in Sawyer.
Collision model.png

As in the figure above, each of Sawyer's link has its own collision block which is slightly bigger than the size of that link. When these block comes into contact with each other, collision avoidance model is triggered. The collision blocks can be visualized in RVIZ by setting the Planned Path field under MotionPlanning and enabling the field Collision Enabled.
The next collision model involves the detection of two types of collisions - impact and squish. Impact is detected when a sudden change in torque is sensed across any of the joint. This can be related to a scenario in which a moving hand collides with a human. Here, the sudden change in torque is sensed during the impact and the robot comes to a stop for 2 seconds before attempting to move again. Squish is detected when joint tries to press against a stationary object. For instance, when a robot arm tries to push a wall, the torque applied across the joint increases and it immediately stops when the applied torque is greater than a threshold. It resumes its motion after 2 seconds.
The rethink log records these information.

[2017-01-12T14:31:32.807793-0500] [WARN] (/collision/right/joint_collision_estimator_right,JointCollisionEstimator.cpp:746) | impact: 0.885333 > 0.750000, largest contributor: right_j2, with value: 0.480856

This log information indicates that an impact was detected when the torque applied across the right_j2 joint is greater than 0.75 Nm. Similarly the corresponding message logged for squish is

[2017-01-12T14:28:20.933828-0500] [WARN] (/collision/right/joint_collision_estimator_right,JointCollisionEstimator.cpp:773) | squish on joint right_j1 - 20.110 > 20.000

These collision information can also be viewed in rqt_console. The images below show the impact and squish logged in rqt_console.

Impact.png

Squish.png

The final collision model is high speed scaling. This is to avoid the collisions of right limb moving at higher speeds. The collision blocks for this purpose is higher than the orginal collision blocks. The collision detection happens when the speed of the limb in cartesian space is higher than 0.2 m/s. In order to avoid the collision, the corresponding velocities are scaled down and converted back as position commands.

To disable the collision avoidance on a right arm, you need to publish an empty message at greater than 5hz to the topic, /robot/limb/right/suppress_collision_avoidance

For eg, the command to suppress collision avoidance on the right arm would be:

$ rostopic pub /robot/limb/right/suppress_collision_avoidance std_msgs/Empty -r 10

The collision avoidance will stay suppressed as long as this is being published

Gravity Compensation Torques

In order to oppose the effect of gravitational force acting across Sawyer's arm, gravity compensation torques have to be applied across that arm. This is a basic mode that is active from the time the robot is enabled. The built-in gravity compensating model uses KDL for calculating the gravity compensation torques, these are found using an internal spring model and applied in conjunction with the torques from KDL. These gravity compensation torques are passed directly to the JCB through a separate channel and are applied irrespective of the controller being active.

The gravity compensation torques are available via the topic robot/limb/right/gravity_compensation_torques of message type intera_core_msgs/SEAJointState

$ rostopic echo robot/limb/right/gravity_compensation_torques # of message type intera_core_msgs/SEAJointState

In order to disable the gravity compensation torques, an empty message should be published to the topic /robot/limb/right/suppress_gravity_compensation at greater than 5 Hz.

$ rostopic pub -r 10 /robot/limb/right/suppress_gravity_compensation std_msgs/Empty


The fields of the Gravity Compensation Torques message:

commanded_position: Commanded Position from RealTime Loop

commanded_velocity: Commanded Velocity from RealTime Loop

commanded_effort: Commanded Effort from RealTime Loop. In torque control mode this will be the torques you commanded. 
                  In position control mode this is the integral effort applied achieving the goal positions.

actual_position: Measured Position from RealTime Loop

actual_velocity: Measured Velocity from RealTime Loop

actual_effort: Measured Effort from RealTime Loop via the Spring Deflection Sensors in each Series Elastic Actuator

gravity_model_effort: Gravity Compensation Torques Commanded

hysteresis_model_effort: Spring Compensation Torques Commanded. This is the hysterisis effort applied to account for spring joint j1

crosstalk_model_effort: Joint Crosstalk Compensation. Present here is minimal compensation for joint j1 crosstalk caused by the arm's downstream joints

hystState: A variable used in calculating the hysteresis model.

Zero-G mode

Zero-G mode can often be confused with the mode obtained by disabling the gravity compensation torques. By default, the gravity compensation torques will always be applied when the robot is enabled. In Zero-G mode, the controllers are disabled and so the arm can be freely moved across. In this case, the effect of gravity would be compensated by the gravity compensation model applying gravity compensation torques across the joints, there would be no torques from the controllers since they would not be active, and so the arm can be moved freely around, hence the name.

The Zero-G mode can be enabled by grasping the cuff over its groove or press circle button on navigators,

Sawyer Training Cuff.png SDK Navigator.png


Unlike the gravity compensation model, the Zero-G mode cannot be directly disabled. The cuff interaction has to be disabled in order to disable the Zero-G. Publishing an empty message to the topic /robot/limb/right/suppress_cuff_interaction at greater than 5Hz, disabled the cuff interaction.

rostopic pub -r 10 /robot/limb/right/suppress_cuff_interaction std_msgs/Empty