Baxter-2
- This page describes how to use our Baxter system. Expected readers are my students (e.g. students in the CMU-Humanoids course).
- System
- Using Baxter
- EMERGENCY
- CUI-tool
- Built-in commands
- Pose representation
- External scripts
- Writing a script
- Get current joint angles
- Get end-effector pose by solving forward kinematics
- Example of inverse kinematics
- Gripper control
- Move arm to target joint angles
- Move arm to target end-effector pose
- Move arm to follow a target joint-angular trajectory
- Move arm to follow a target end-effector trajectory
- Plan a collision free path to a target end-effector pose
System †
- LZ
- Operating computer of Baxter (and Lulzbot)
- Hostname: lz
- Ubuntu 14.04, ROS indigo, Baxter SDK, Robotiq SDK, and my tools are installed.
- CGA12
- Operating computer of Baxter
- DNS server of the lab
- Hostname: cga12i
- Ubuntu 14.04, ROS indigo, Baxter SDK, Robotiq SDK, and my tools are installed.
- Baxter
- Hostname of internal computer: bx1
- Left gripper: Robotiq gripper 2-FINGER-85
- Right gripper: Electric parallel gripper for Baxter
- Baxter Research Robot Wiki
- Robotiq gripper
- Hostname of controller: rq1
- Sentis M100
- Hostname: m100
- Depth sensor
- Mounted on Left Wrist
- Optical skin
- Attached on all four fingers, controlled by two Raspberry Pi
- Raspberry Pi on RIGHT hand: aypi1
- Raspberry Pi on LEFT hand: aypi2
- Stereo camera
- Mounted on Right Wrist
- Note
- In order to obtain an IP address of a computer, use ping to the hostname.
Using Baxter †
Preparation †
- Put E-STOP around you or ask someone to hold it.
- (Baxter, Robotiq, Sentis M100, LZ are always ON. Do not turn them off after experiments.)
- Plug-in the Xbox wireless receiver to LZ, and pair it with the Xbox wireless controller.
- Log in to LZ or CGA12. If someone already logged in with your account, just UNLOCK. Maybe you need to press Alt+Ctrl+F8 or F9 before unlock. If someone already logged in with other account, SWITCH USER and log in with your account.
- Do not shutdown the computer. Someone's work might be lost.
Launch the programs †
From BX-GUI †
(Note: bx_gui.py just sends command. It does not have a function to synchronize the robot and software status. Don't trust too much.)
- Open a terminal.
- Launch BX-GUI. Type on the terminal:
Note: $ denotes a prompt of a terminal (don't type it).$ ros $ rosrun lfd_trick bx_gui.py
- Click "Init"
- Click "enable" (WARNING: ACTUATORS WILL BE ACTIVATED!!)
- Click "system" (launching lfd_trick/bx_real.launch)
- (Optional) Click "rviz"
Note: Real Baxter and the model in RViz are synchronizing. Check it by moving the real robot. - (Optional) Click (aypip1) "stream", wait until the camera stream starts.
- (Optional) Click (vskin1) "start", finger vision windows are opened.
- (Optional) Same as (aypip2), (vskin2).
- Launch CUI-tool. Type on a new terminal:
Note: Calibrations of grippers may be executed.$ ros $ bxmaster $ cd ros_ws/lfd_trick $ scripts/cui_tool.py
- When "Done: setup" is displayed, press enter to continue.
From Command Line †
- Open a terminal.
- Activate the robot, and launch the core programs. Type on the terminal:
Note: $ denotes a prompt of a terminal (don't type it).$ ros $ bxmaster $ bxrun -e #WARNING: ACTUATORS WILL BE ACTIVATED!! $ roslaunch lfd_trick bx_real.launch
- Open a new terminal (a new tab is okay).
- Launch RViz (a display program). Type on the terminal:
Note: Real Baxter and the model in RViz are synchronizing. Check it by moving the real robot.$ ros $ bxmaster $ rviz
- Launch CUI-tool. Type on the terminal:
Note: Calibrations of grippers may be executed.$ ros $ bxmaster $ cd ros_ws/lfd_trick $ scripts/cui_tool.py
- When "Done: setup" is displayed, press enter to continue.
CUI-tool †
Now you will see:
Baxter:trick or quit|L>
This is a command-line console of Baxter. You can use the robot without re-connecting to the robot and calibrations.
Try a joy-stick control. Just type j.
> j
How to use the joy-stick? Press "h" on the terminal.
To quit the joy-stick control mode, press the START button on the XBox controller or press q on the terminal.
Quit the System †
- On CUI-tool, type:
Answer n (NO) if you are asked questions.> quit
- Quit RViz.
- From BX-GUI:
- Quit finger vision programs.
- Quit camera streams from Raspberry Pi.
- Move the arms to the safe poses to prepare for deactivation.
- Click (Baxter) "kill" (This should be before (Baxter) "disable")
- Click (Baxter) "disable" (WARNING: ACTUATORS WILL LOOSE POWER!)
- Click "Exit"
- From command line:
- Go to the terminal where you launched roslaunch lfd_trick bx_real.launch, and press Ctrl+C.
- Deactivate the actuators. Move the arms to the safe poses to prepare for deactivation. Type:
$ bxrun -d #WARNING: ACTUATORS WILL LOOSE POWER!
- Close terminals, editors, and programs that you opened.
- Unplug the Xbox wireless receiver.
- Lock the screen.
- That's it. DO NOT TURN OFF Baxter, Robotiq, Sentis M100, LZ, CGA12, and other stuff.
EMERGENCY †
When Baxter performs an unexpected behavior and you feel it is danger, press the E-STOP as soon as possible. Note that this will deactivate the robot, so the arms move downward because of the gravity.
How to recover the robot after pressing E-STOP:
- Follow the quit procedure. DANGER: Make sure that lfd_trick/bx_real.launch is turned off. Otherwise the robot may move suddenly to a cached pose.
- Activate E-STOP (rotate the handle).
- Start from the beginning.
CUI-tool †
More details about CUI-tool.
On CUI-tool, you can execute built-in commands (defined in lfd_trick/scripts/cui_tool.py) and external scripts (defined in lfd_trick/scripts/motions/).
Built-in commands †
- quit: Quit CUI-tool
- r,l: Switch the current arm to right or left.
- c EQUATION: Evaluate EQUATION. Just an equation is allowed, i.e. assignment is not allowed.
- e EXPRESSION: Execute EXPRESSION. Any expression is allowed including assignments.
- q: Print current joint angles of current arm. Output is a list of 7 elements as a Baxter arm has 7 joints.
- x: Print current end-effector pose of current arm.
- xe: Print current fingertip pose of current arm. Fingertip is a fixed point on the end-effector. (WARNING: This is inaccurate as the fingertips are replaced)
- moveq LIST: Move current arm to specified joint angles. LIST should be a list of 7 elements each of that is a joint angle.
- movex LIST: Move end-effector of current arm to specified pose. LIST should be a list of 7 elements consisting of position and orientation.
- movexe LIST: Move fingertip of current arm to specified pose. LIST should be a list of 7 elements consisting of position and orientation. (WARNING: This is inaccurate as the fingertips are replaced)
- grip POS,EFFORT: Move gripper of current arm to specified position. POS is a value like 0.0 or 0.08 (0 cm and 8 cm), EFFORT is a max effort (force) to use, e.g. 20.
For example,
Baxter:trick or quit|L> q Left arm joint angles: [1.034286545050049, 0.05560680349731446, -0.07171360175170899, 1.5911215704162598, 2.4528352770263675, 0.09395632315063478, 0.01457281746826172]
Pose representation †
In lfd_trick including CUI-tool, a pose is defined as a list consists of a position (x,y,z) and an orientation represented as quaternion (qx,qy,qz,qw): pose=[x,y,z,qx,qy,qz,qw].
External scripts †
External scripts (Python) are stored in ros_ws/lfd_trick/scripts/motions. E.g. you can find j.py in that directory.
The students of the Humanoids course (2017 spring) must use [...]/motions/hm17 directory. Adding a new directory for each project is recommended.
For example, let's assume you created [...]/motions/hm17/test1.py. Execute it on CUI-tool as:
Baxter:trick or quit|L> hm17.test1 ARG1, ARG2, ...
Slash (/) in path is replaced by dot (.), and .py is omitted. Arguments (ARG1, ARG2, ...) may follow that are passed to the script. If ARG1 is an expression, it is evaluated and then passed to the script. For example,
Baxter:trick or quit|L> hm17.test1 1+1, 2+2
will pass arguments (2,4) to the script test1.py.
- NOTE
- When creating a directory, it is necessary to put an empty file with a filename __init__.py.
Writing a script †
A template of script looks like:
#!/usr/bin/python
from core_tool import *
def Help():
return '''Template of script.
Usage: template'''
def Run(t,*args):
print t
You need to define two functions: Help and Run. Help is a function that returns a help message describing about the script and the usage. Run is the main function executed when the script is called in CUI-tool. Run has arguments t which is a Core-tool object maintaining ROS connections, etc., and args which are given from the prompt of CUI-tool. For example, when you execute type:
Baxter:trick or quit|L> hm17.test1 10, 20
Run in hm17/test1.py is called with arguments (t,10,20). args[0] gives 10 and args[1] gives 20.
The Core-tool object provides an interface to control the robot. Some details are described below.
Note that these scripts are stored in [...]/motions/ex directory.
Get current joint angles †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Get current joint angles.
Usage: ex.get_q1 [ARM]
ARM: RIGHT or LEFT, default=t.robot.Arm
'''
def Run(t,*args):
arm= args[0] if len(args)>0 else t.robot.Arm
q= t.robot.Q(arm=arm) #Get current joint angles
print 'Joint angles of {arm}-arm= {q}'.format(arm=LRToStr(arm), q=q)
Execution result:
Baxter:trick or quit|L> ex.get_q1 RIGHT Joint angles of Right-arm= [-1.1861506428771973, -0.06864564017944337, 0.07746602969970703, 1.7410681922607423, -2.5571459704833988, 0.03873301484985352, 0.05560680349731446]
Get end-effector pose by solving forward kinematics †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Get end-effector pose by solving forward kinematics.
Note: pose = [x,y,z,qx,qy,qz,qw] (position, quaternion)
Usage: ex.get_x1 [ARM [, ANGLES]]
ARM: RIGHT or LEFT. default=t.robot.Arm
ANGLES: Array of joint angles (7 elements). default=t.robot.Q(arm=ARM)
'''
def Run(t,*args):
arm= args[0] if len(args)>0 else t.robot.Arm
q= args[1] if len(args)>1 else t.robot.Q(arm=arm)
x= t.robot.FK(q=q, arm=arm)
print 'End-effector pose of {arm}-arm= {x}'.format(arm=LRToStr(arm), x=list(x))
Execution result:
Baxter:trick or quit|L> ex.get_x1 End-effector pose of Left-arm= [0.064122679887232609, 0.65801714588438465, -0.33855792411485697, 0.27713757655214427, 0.96033292654954627, -0.020645823069559248, 0.02300399611736852]
Baxter:trick or quit|L> ex.get_x1 RIGHT,[0.0]*7 End-effector pose of Right-arm= [0.81821298738435877, -1.0045592698677348, 0.32042065046352775, 0.26564717484843692, 0.65228131613490492, -0.27325006910534255, 0.65520612241514109]
Example of inverse kinematics †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Example of inverse kinematics.
Usage: ex.ik1 ARM, POSE
ARM: RIGHT or LEFT
POSE: Array of target pose = [x,y,z,qx,qy,qz,qw] (position, quaternion)
'''
def Run(t,*args):
arm= args[0]
x_trg= args[1]
q= t.robot.IK(x_trg, arm=arm)
print 'IK solution= {q}'.format(q=q)
Execution result:
Baxter:trick or quit|L> ex.ik1 RIGHT, [0.5,-0.4,0.2, 0.0,1.0,0.0,0.0] IK solution= [-0.56045961 -0.11890099 1.70077447 2.08906608 -1.3947972 1.61573216 0.75933024] Baxter:trick or quit|L> ex.ik1 RIGHT, [0.5,-0.4,5.2, 0.0,1.0,0.0,0.0] IK solution= None
None shows there is no IK solution. The target may be out of the movable range of the end-effector.
Gripper control †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Move fingers of gripper to a target position.
Usage: ex.grip1 ARM, POS
ARM: RIGHT or LEFT
POS: Position in meter. 0 is closed
Range of POS (RIGHT): [0.00,0.037]
Range of POS (LEFT): [0.0,0.0855]
'''
def Run(t,*args):
arm= args[0]
pos= args[1]
t.robot.MoveGripper(pos, arm=arm)
print 'Moving {arm}-gripper to {pos}'.format(arm=LRToStr(arm), pos=pos)
Execution result:
Baxter:trick or quit|L> ex.grip1 LEFT, 0.05 Moving Left-gripper to 0.05 Baxter:trick or quit|L> ex.grip1 RIGHT, 0.01 Moving Right-gripper to 0.01
Move arm to target joint angles †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Move arm to target joint angles.
Warning: Be careful to moving area of robot.
Usage: ex.move_q1 ARM, D_ANGLES
ARM: RIGHT or LEFT, default=t.robot.Arm
D_ANGLES: Array of displacement of joint-angles. [0.0]*7 current angles
'''
def Run(t,*args):
arm= args[0]
dq= args[1]
q= t.robot.Q(arm=arm) #Current joint angles
q_trg= [q[d]+dq[d] for d in range(7)] #Target
print 'Moving {arm}-arm to {q}'.format(arm=LRToStr(arm), q=q_trg)
t.robot.MoveToQ(q_trg, dt=4.0, arm=arm)
Execution result:
Baxter:trick or quit|L> ex.move_q1 RIGHT, [0.1]*7 Moving Right-arm to [-1.525252642907715, 0.29596604542846683, 0.5502233607299805, 1.8882381014343264, -2.2680828385925293, -0.8932525590209962, 0.1368155388671875] Baxter:trick or quit|L> ex.move_q1 RIGHT, [-0.1]*7 Moving Right-arm to [-1.6259273870056155, 0.1956747965270996, 0.44878162623901374, 1.7875633573364258, -2.3676070971008305, -0.9966117694946289, 0.038058270751953116]
Move arm to target end-effector pose †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Move arm to target end-effector pose.
Warning: Be careful to moving area of robot.
Usage: ex.move_x1 ARM, D_POS
ARM: RIGHT or LEFT, default=t.robot.Arm
D_POS: Array of displacement of end-effector position (x,y,z). [0.0]*3 current position
'''
def Run(t,*args):
arm= args[0]
dp= args[1]
x= list(t.robot.FK(arm=arm)) #Current end-effector pose
x_trg= [x[d]+dp[d] for d in range(3)] + x[3:] #Target
print 'Moving {arm}-arm to {x}'.format(arm=LRToStr(arm), x=x_trg)
t.robot.MoveToX(x_trg, dt=4.0, arm=arm)
Execution result:
Baxter:trick or quit|L> ex.move_x1 RIGHT, [0.0,0.0,0.05] Moving Right-arm to [0.23439000177890246, -0.59451021860993425, 0.0077860696028871426, 0.013226960056151966, 0.6958639397310612, -0.021558522231107168, 0.71772812055042723] Baxter:trick or quit|L> ex.move_x1 RIGHT, [0.0,0.0,-0.05] Moving Right-arm to [0.23536243735360643, -0.59439201308211076, -0.041323987508458088, 0.012551068665841474, 0.69519516371593415, -0.021306117181770497, 0.71839557653980335]
Move arm to follow a target joint-angular trajectory †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Move arm to follow a target joint-angular trajectory.
Warning: Be careful to moving area of robot.
Usage: ex.follow_q_traj1
'''
def Run(t,*args):
arm= RIGHT
q= list(t.robot.Q(arm=arm)) #Current joint angles
q_traj= [
q,
[q[d]+(0.1,0.0,0.0,0.0,0.0,0.0,0.0)[d] for d in range(7)],
[q[d]+(-0.1,0.0,0.0,0.0,0.0,0.0,0.0)[d] for d in range(7)],
[q[d]+(0.0,0.1,0.0,0.0,0.0,0.0,0.0)[d] for d in range(7)],
[q[d]+(0.0,-0.1,0.0,0.0,0.0,0.0,0.0)[d] for d in range(7)],
q
]
t_traj= [0.0, 3.0, 6.0, 9.0, 12.0, 15.0]
t.robot.FollowQTraj(q_traj, t_traj, arm=arm)
Execution result:
Baxter:trick or quit|L> ex.follow_q_traj1
Robot will follow the trajectory.
Move arm to follow a target end-effector trajectory †
#!/usr/bin/python
from core_tool import *
def Help():
return '''Move arm to follow a target end-effector trajectory.
Warning: Be careful to moving area of robot.
Usage: ex.follow_x_traj1
'''
def Run(t,*args):
arm= RIGHT
x= list(t.robot.FK(arm=arm)) #Current end-effector pose
x_traj= [
x,
[x[0],x[1]+0.05,x[2]] + x[3:],
[x[0],x[1],x[2]-0.05] + x[3:],
[x[0],x[1]-0.05,x[2]] + x[3:],
[x[0],x[1],x[2]+0.05] + x[3:],
x
]
t_traj= [0.0, 3.0, 6.0, 9.0, 12.0, 15.0]
t.robot.FollowXTraj(x_traj, t_traj, arm=arm)
Execution result:
Baxter:trick or quit|L> ex.follow_x_traj1
Robot will follow the trajectory.
Plan a collision free path to a target end-effector pose †
This is an advanced and exciting example!
#!/usr/bin/python
from core_tool import *
def Help():
return '''Plan a collision free path to a target end-effector pose.
Warning: Be careful to moving area of robot.
Usage: ex.plan_x1
'''
def Run(t,*args):
#First we make a planning scene to compute collision.
#Baxter is already involved.
#Add a table to the planning scene
table_dim= [0.5,1.8,0.05]
x_table= [0.84,0.0,0.723-0.902, 0.0,0.0,0.0,1.0] #90.2cm is the height of Baxter pedestal
table_attr={
'x': x_table,
'bound_box': {
'dim':table_dim,
'center':[0.0,0.0,-table_dim[2]*0.5, 0.0,0.0,0.0,1.0]
},
'shape_primitives': [
{
'kind': 'rtpkCuboid',
'param': [l/2.0 for l in table_dim], #[half_len_x,half_len_y,half_len_z]
'pose': [0.0,0.0,-table_dim[2]*0.5, 0.0,0.0,0.0,1.0],
},
],
}
#Add table to an internal dictionary:
t.SetAttr('table',table_attr)
#Add table to the planning scene:
t.SetAttr(CURR,'scene', LUnion(t.GetAttrOr([],CURR,'scene'),['table']))
#Add a box to the planning scene
box_dim= [0.3,0.3,0.3]
x_box= [0.7,0.2,-0.05, 0.0,0.0,0.0,1.0]
box_attr={
'x': x_box,
'bound_box': {
'dim':box_dim,
'center':[0.0,0.0,0.0, 0.0,0.0,0.0,1.0]
},
'shape_primitives': [
{
'kind': 'rtpkCuboid',
'param': [l/2.0 for l in box_dim], #[half_len_x,half_len_y,half_len_z]
'pose': [0.0,0.0,0.0, 0.0,0.0,0.0,1.0],
},
],
}
#Add box to an internal dictionary:
t.SetAttr('box',box_attr)
#Add box to the planning scene:
t.SetAttr(CURR,'scene', LUnion(t.GetAttrOr([],CURR,'scene'),['box']))
#Visualize scene:
t.ExecuteMotion('viz','')
#Move to the target with planning a collision free path:
arm= LEFT
x_trg= [0.72,-0.12,0.14, 0.6340761624607465,0.7359104869964589,-0.12067513962937848,0.20450106601951204]
lw_xe= [0.0,0.0,0.0, 0.0,0.0,0.0,1.0]
dt= 5.0 #Duration
conservative= True #Ask Yes/No before moving
t.ExecuteMotion('move_to_x', x_trg, dt, lw_xe, arm, {}, conservative)
print 'Clear the planning scene?'
if t.AskYesNo():
#Remove table, box from the planning scene
t.SetAttr(CURR,'scene', LDifference(t.GetAttrOr([],CURR,'scene'),['table','box']))
#Refresh visualization:
t.ExecuteMotion('viz','')
Execution result:
Baxter:trick or quit|L> ex.plan_x1
First the robot plans a path that does not collide with environment (objects in the planning scene). It looks like:
Before plan: Objects (table, box) are added to the planning scene. The target is around the left of the box.
After plan: A trajectory was planned (see the sky-blue line).
After execution: The robot followed the planned trajectory.