This tutorial describes how to create different interaction control behaviors using example scripts.
Contents
Impedance/Force Control Examples
Interaction controller in Intera enables impedance or force control at the endpoint of the arm. The following tutorial demonstrates using example scripts to create different interaction control behaviors.
An impedance control example with low stiffness along vertical direction.
Default Interaction Control Motion
The default interaction control mode performs impedance control at the endpoint with maximum stiffness in all 6 directions. The following command uses go_to_joint_angles_in_contact.py script to move the arm from the current configuration to a specified configuration with the default interaction control behavior. A trajectory message along with interaction parameters is sent to Motion Controller. Note that without any extra arguments nullspace stiffness values, default values are used.
$ rosrun intera_examples go_to_joint_angles_in_contact.py -q 0 -0.8 0 1.6 0 0.8 0
-q 0 -0.8 0 1.6 0 0.8 0
specifies the target arm joint angles. More arguments can be used to set other options (speed, interaction parameters, and etc.), which can be found by using -h
argument for the script.
Z-axis Compliance in the End Effector Frame
In impedance control, a desired stiffness value can be specified for each of 6 directions. The following command demonstrates having a low stiffness (i.e., more compliance) only along z-axis of end effector (TCP) frame.
$ rosrun intera_examples set_interaction_options.py -m 1 1 0 1 1 1 -k 1300 1300 500 30 30 30 -ef -kn 0 0 0 0 0 0 0
-m 1 1 0 1 1 1
and -k 1300 1300 500 30 30 30
set the direction along z-axis to have a specified stiffness of 500 while maximum stiffness values will be computed for the rest of directions. -ef
sets end effector frame to be the reference frame for impedance control. -kn 0 0 0 0 0 0 0
sets the nullspace stiffness to zero.
Z-axis Force in the End Effector Frame
Force control is usually performed only along a single direction. The following command demonstrates how to apply force only along the z-axis of end effector frame using the set_interaction_options.py script. This script sends a Interaction Control command directly to the realtime loop; this sets the arm into interaction control mode but does not command the arm to move. The endpoint remains in impedance control mode with maximum stiffness for the rest of directions. The nullspace stiffness is set to zero in this example.
$ rosrun intera_examples set_interaction_options.py -md 1 1 2 1 1 1 -ef -f 0 0 30 0 0 0 -kn 0 0 0 0 0 0 0
-md 1 1 2 1 1 1
and -ef
set the translational direction of end effector's z-axis to force control mode. -f 0 0 30 0 0 0
sets the force command along z-axis to be 30 Newtons. -kn 0 0 0 0 0 0 0
sets the nullspace stiffness to zero.
Z-axis Impedance Control with Force Limits in the End Effector Frame
As a hybrid mode between impedance and force mode, there is Impedance Control with Force Limit mode. The following command demonstrates setting a force limit along the end effector's z-axis during impedance control.
$ rosrun intera_examples set_interaction_options.py -md 1 1 3 1 1 1 -ef -f 0 0 30 0 0 0 -kn 0 0 0 0 0 0 0
-md 1 1 3 1 1 1
and -ef
set the translational direction along z-axis of end effector frame to be in impedance with force limit mode. -f 0 0 30 0 0 0
sets the force limit along the z-axis to be 30 Newtons. -kn 0 0 0 0 0 0 0
sets the nullspace stiffness to zero.
Constrained Zero-G Examples
Regular zero-g mode of Sawyer can be interpreted as having zero stiffness at the endpoint and in the nullspace allowing the endpoint and nullspace free movement in all directions. Constrained zero-g mode only sets part of the stiffness values set to zero. In this mode, the movement about directions with non-zero stiffness values is constrained while the arm is free to move in the directions with zero stiffness. The following examples demonstrate how to use constrained_zeroG.py script to generate different constrained zero-G behaviors. Note that the script sets the nullspace stiffness values to default values for maintaining the elbow position, by default.
A constrained zero-G example with free orientation.
Constrained Zero-G in Position
The following command sets the endpoint to move freely only in the translational directions. In the rest of the directions (i.e., rotational directions), the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -p
-p
sets the stiffness gains for all three translational directions to 0.
Constrained Zero-G in Position along the Base Frame Z-axis
The following command sets the endpoint to move freely only along z-axis of the base frame. In the rest of the directions, the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -pz
-pz
sets the stiffness gain for the translational direction along z-axis to 0.
Constrained Zero-G in Orientation
The following command sets the endpoint to move freely only about the rotational directions. In the rest of the directions (i.e., translational directions), the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -o
-o
sets the stiffness gains for all three rotational directions to 0.
Constrained Zero-G in Orientation about Base Frame X-axis
The following command sets the endpoint to move freely only about x-axis of the base frame. In the rest of the directions, the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -ox
-ox
sets the stiffness gain for the rotational direction about x-axis of base frame to 0.
Constrained Zero-G in Horizontal Plane (XY)
The following command sets the endpoint to move freely only on XY plane of the base frame (i.e., along both x and y axes). In the rest of the directions, the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -ph
-ph
sets the stiffness gain for the horizontal directions (x and y axes) to be 0. Alternatively, -x -y
can be used.
Constrained Zero-G in the Nullspace
The following command sets the arm to move freely only in the nullspace while the endpoint remains in impedance control with maximum stiffness.
$ rosrun intera_examples constrained_zeroG.py -ns
-ns
sets all of the nullspace stiffness gains to 0.