PR2 Beta Training Workshop on ROS & PR2
Videos now available (more to come): Videos |
Location: Willow Garage Menlo Park, CA.
Date: Monday May 24 2010 - Friday May 28 2010
Time: 9am -6pm
Registration: PR2 Beta Program Recipients
Contents
Prerequisites
This is a hands-on workshop, with programming exercises for using ROS and the PR2.
Attendees will need prior experience with ROS:
Schedule
(Under construction and subject to change)
Monday
8:30 AM Breakfast
9:00 AM ROS Overview ros_overview.pdf
9:30 AM PR2 Safety video
10:00 AM BREAK
10:15 AM PR2 Administrative Tasks pr2_admin.pdf, pr2_admin_handout.pdf
In this tutorial we will introduce the things an admin for the PR2 will need to know.
12:00 PM Lunch with Willow
1:00 PM Bring up PR2 and Debugging PR2 pr2_robot/Tutorials/Starting up the PR2
Using and understanding common PR2 tools:
- pr2_dashboard
- run stops
- teleop
- useful apps.
2:15 PM BREAK
2:30 PM PR2 and ROS Tips and Tricks tips_and_tricks.pdf
3:00 PM PR2 and rviz rviz.pdf
In this tutorial we will introduce rviz, our 3d visualization environment.
4:30 PM PR2 and TF tf.pdf
In this tutorial we will provide an introduction to the concepts of the tf library, provide examples of common use cases and the tf api, and give guidance for debugging common tf problems.
5:30 BREAK
5:45 PM PR2 Calibration pr2_calibration/Tutorials/Calibrating the PR2 calibrating_pr2.pdf
In this tutorial we will cover how to calibrate your PR2 out of the box.
7:00 PM Dinner
Tuesday
8:30 AM Breakfast
9:00 AM Navigation navigation.pdf
Autonomous navigation is a useful building block for many applications. This tutorial will give an overview of the navigation stack included with ROS, provide step-by-step instructions for running autonomous navigation applications on the PR2 robot, and discuss approaches for tasking the robot to achieve a navigation goal.
10:45 BREAK
11:00 AM Moving the mechanism moving_mechanism.pdf
In this tutorial we will introduce methods of moving and controlling the PR2 mechanism.
Moving the Mechanism Python Scripts: Base Gripper Head Torso Teleop | All None
Moving the Base
1 #! /usr/bin/python
2 import time
3 import roslib
4 roslib.load_manifest('rospy')
5 roslib.load_manifest('geometry_msgs')
6 import rospy
7 from geometry_msgs.msg import *
8
9 rospy.init_node('move_the_base', anonymous=True)
10
11 pub = rospy.Publisher('base_controller/command', Twist)
12 time.sleep(1)
13
14 movement = Twist()
15 movement.linear.x = 0.1
16 start_time = rospy.get_rostime()
17 while rospy.get_rostime() < start_time + rospy.Duration(3.0):
18 pub.publish(movement)
19 time.sleep(0.01)
20 pub.publish(Twist()) # Stop
Moving the Gripper
1 #! /usr/bin/python
2 import roslib
3 roslib.load_manifest('mm_teleop')
4
5 import rospy
6 import actionlib
7 from actionlib_msgs.msg import *
8 from pr2_controllers_msgs.msg import *
9
10 rospy.init_node('move_the_gripper', anonymous=True)
11
12 client = actionlib.SimpleActionClient(
13 'r_gripper_controller/gripper_action', Pr2GripperCommandAction)
14 client.wait_for_server()
15
16 client.send_goal(Pr2GripperCommandGoal(
17 Pr2GripperCommand(position = 0.0, max_effort = -1)))
18 client.wait_for_result()
19
20 result = client.get_result()
21 did = []
22 if client.get_state() != GoalStatus.SUCCEEDED:
23 did.append("failed")
24 else:
25 if result.stalled: did.append("stalled")
26 if result.reached_goal: did.append("reached goal")
27 print ' and '.join(did)
Moving the Head
1 #! /usr/bin/python
2 import roslib
3 roslib.load_manifest('mm_teleop')
4
5 import rospy
6 import actionlib
7 from actionlib_msgs.msg import *
8 from pr2_controllers_msgs.msg import *
9 from geometry_msgs.msg import *
10
11 rospy.init_node('move_the_head', anonymous=True)
12
13 client = actionlib.SimpleActionClient(
14 '/head_traj_controller/point_head_action', PointHeadAction)
15 client.wait_for_server()
16
17 g = PointHeadGoal()
18 g.target.header.frame_id = 'base_link'
19 g.target.point.x = 1.0
20 g.target.point.y = 0.0
21 g.target.point.z = 1.0
22 g.min_duration = rospy.Duration(1.0)
23
24 client.send_goal(g)
25 client.wait_for_result()
26
27 if client.get_state() == GoalStatus.SUCCEEDED:
28 print "Succeeded"
29 else:
30 print "Failed"
Moving the Torso
1 #! /usr/bin/python
2 import roslib
3 roslib.load_manifest('mm_teleop')
4
5 import rospy
6 import actionlib
7 from actionlib_msgs.msg import *
8 from pr2_controllers_msgs.msg import *
9
10 rospy.init_node('single_joint_position', anonymous=True)
11
12 client = actionlib.SimpleActionClient('torso_controller/position_joint_action',
13 SingleJointPositionAction)
14 client.wait_for_server()
15
16 client.send_goal(SingleJointPositionGoal(position = 0.2))
17 client.wait_for_result()
18 if client.get_state() == GoalStatus.SUCCEEDED:
19 print "Success"
Teleop skeleton
1 #! /usr/bin/env python
2
3 import roslib
4 roslib.load_manifest('mm_teleop')
5 from pr2_controllers_msgs.msg import *
6 import rospy
7 import actionlib.action_client
8 import termios, tty, sys, select
9
10 # My tricks for making Ctrl-C work seamlessly
11 import atexit
12 atexit.register(rospy.signal_shutdown, 'exit')
13
14
15 def getKey():
16 settings = termios.tcgetattr(sys.stdin)
17 try:
18 #tty.setraw(sys.stdin.fileno())
19 tty.setcbreak(sys.stdin.fileno())
20 select.select([sys.stdin], [], [], 0)
21 key = sys.stdin.read(1)
22 return key
23 finally:
24 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
25
26
27 def print_usage():
28 print """Usage:
29
30 q - quit
31 h - print usage
32
33 Base
34 Translate Rotate
35 i u o
36 j k l
37
38 Head Laser
39 e a - Scan quickly
40 s d f z - Scan slowly
41
42 Grippers
43 Left Right
44 p - open [ - open
45 ; - close ' - close
46 P - float { - float
47 : - close lightly " - close lightly
48
49 Arms: Run trajectory 1, 2, 3, ...
50
51 """
52
53
54
55 def main():
56 print_usage()
57 rospy.init_node('teleop_the_robot', disable_signals=True, anonymous=True)
58 while True:
59 key = getKey()
60 #print "key:", key, ord(key)
61 if key == 'q' or key == chr(3):
62 return
63 if key == 'h':
64 print_usage()
65
66 if key == 'i': # Base forward
67 pass
68 if key == 'k': # Base backwards
69 pass
70 if key == 'j': # Base left
71 pass
72 if key == 'l': # Base right
73 pass
74 if key == 'u': # Base yaw left
75 pass
76 if key == 'o': # Base yaw right
77 pass
78
79 if key == 'e': # Head up
80 pass
81 if key == 'd': # Head down
82 pass
83 if key == 's': # Head left
84 pass
85 if key == 'f': # Head right
86 pass
87
88 if key == 'a': # Laser quickly
89 pass
90 if key == 'z': # Laser slowly
91 pass
92
93 if key == 'p': # L gripper open
94 pass
95 if key == ';': # L gripper close
96 pass
97 if key == 'P': # L gripper float
98 pass
99 if key == ':': # L gripper close lightly
100 pass
101 if key == '[': # R gripper open
102 pass
103 if key == "'": # R gripper close
104 pass
105 if key == '{': # R gripper float
106 pass
107 if key == '"': # R gripper close lightly
108 pass
109
110 if key >= '1' and key <= '9':
111 trajectory_number = int(key)
112
113
114 if __name__ == '__main__':
115 try:
116 main()
117 except KeyboardInterrupt:
118 pass
1:00 PM Lunch with Willow
2:00 PM Processing camera data camera_processing.pdf
In this tutorial we will introduce the PR2 camera suite, showing how to configure the cameras and process the data they produce.
4:00 BREAK
4:15 PM Processing laser and point cloud data laser_processing.pdf
In this tutorial we will introduce the PR2 sensor suite, showing how to configure the lasers and process the data they produce. Example PCL source code tutorial: PCL Tutorial
6:00 PM Q&A and free time with PR2s
6:30 PM Dinner
Wednesday
8:30 AM Breakfast
9:00 AM Simulation pr2_simulator.pdf
In this tutorial we will introduce how to bring up a PR2 in simulation, clarify differences between the hardware and the simulator, and how to debug controllers in simulation. And maybe touch on the underlying solvers used in Gazebo.
10:00 AM Writing Awesome Code
12:00 PM Lunch
3:00 PM Get ready for party
Thursday
8:30 AM Breakfast
9:00 AM Writing Awesome Code
1:00 PM Lunch
2:00 PM Beta recipients will give 15 minute presentations discussing their future plans for the PR2.
5:30 PR2 Free time
6:30 Dinner
Friday
8:30 AM Breakfast
9:00 AM How to install your PR2 base station in your lab basestation.pdf, basestation_handout.pdf NetDiagram.pdf
In this tutorial we will introduce the PR2 basestation, explain why it is necessary, how to set it up, and how to make use of it.
10:45 BREAK
11:00 AM How to reinstall PR2 pr2_reinstall.pdf
In this tutorial we will introduce how to wipe everything and start over.
12:00 PM Lunch
1:00 PM Service and Toolkit pr2_maintenance.pdf
In this tutorial we will cover how to service and maintain your PR2.
1:45 PM Adding sensors to PR2 and modularity adding_sensor.pdf
In this tutorial we will cover an example of how to add a sensor to the PR2.
3:30 PM BREAK
3:45 PM PR2 Maintenance Demos (see pr2_maintenance.pdf above)
5:30 PM Program Close