35 import roslib; roslib.load_manifest(
'calibration_launch')
    50     msg.header.stamp = rospy.Time(secs, 0)
    61         chain_state_pub = rospy.Publisher(
"chain1/chain_state", sensor_msgs.msg.JointState)
    68         chain_state_pub.publish(
build_msg(JointState, 1))
    75         chain_state_pub.publish(
build_msg(JointState, 2))
    80         print "Calling user callback"    91         manager.enable(verbose=
False)
    93         cam_info_pub = rospy.Publisher(
"cam1/camera_info", sensor_msgs.msg.CameraInfo)
    94         features_pub = rospy.Publisher(
"cam1/features", calibration_msgs.msg.CalibrationPattern)
    95         image_pub    = rospy.Publisher(
"cam1/image",    sensor_msgs.msg.Image)
   100         manager.enable(verbose=
True)
   102         cam_info_pub.publish(
build_msg(CameraInfo, 1))
   103         features_pub.publish(
build_msg(CalibrationPattern, 1))
   109         manager.enable(verbose=
True)
   111         cam_info_pub.publish(
build_msg(CameraInfo, 2))
   112         features_pub.publish(
build_msg(CalibrationPattern, 2))
   117         manager.enable(verbose=
False)
   119         cam_info_pub.publish(
build_msg(CameraInfo, 3))
   120         features_pub.publish(
build_msg(CalibrationPattern, 3))
   126         print "Calling user callback"   137         manager.enable(verbose=
False)
   139         snapshot_pub       = rospy.Publisher(
"laser1/snapshot",       calibration_msgs.msg.DenseLaserSnapshot)
   140         laser_image_pub    = rospy.Publisher(
"laser1/laser_image",    sensor_msgs.msg.Image)
   141         image_features_pub = rospy.Publisher(
"laser1/image_features", calibration_msgs.msg.CalibrationPattern)
   142         joint_features_pub = rospy.Publisher(
"laser1/joint_features", calibration_msgs.msg.JointStateCalibrationPattern)
   143         duration_pub       = rospy.Publisher(
"laser1/laser_interval", calibration_msgs.msg.IntervalStamped)
   148         manager.enable(verbose=
True)
   150         snapshot_pub.publish(
build_msg(DenseLaserSnapshot, 1))
   151         laser_image_pub.publish(
build_msg(Image, 1))
   152         image_features_pub.publish(
build_msg(CalibrationPattern, 1))
   153         joint_features_pub.publish(
build_msg(JointStateCalibrationPattern, 1))
   154         duration_pub.publish(
build_msg(IntervalStamped, 1))
   159         manager.enable(verbose=
True)
   161         snapshot_pub.publish(
build_msg(DenseLaserSnapshot, 2))
   162         laser_image_pub.publish(
build_msg(Image, 2))
   164         joint_features_pub.publish(
build_msg(JointStateCalibrationPattern, 2))
   165         duration_pub.publish(
build_msg(IntervalStamped, 2))
   170         manager.enable(verbose=
False)
   172         snapshot_pub.publish(
build_msg(DenseLaserSnapshot, 3))
   173         laser_image_pub.publish(
build_msg(Image, 3))
   175         joint_features_pub.publish(
build_msg(JointStateCalibrationPattern, 3))
   176         duration_pub.publish(
build_msg(IntervalStamped, 3))
   180     def callback(self, cam_id, msg, interval_start, interval_end):
   181         print "Calling user callback"   187 if __name__ == 
'__main__':
   189     rospy.init_node(
"test_node")
   190     rostest.unitrun(
'pr2_calibration_executive', 
'test_cam_manager',   TestCamManager)
   191     rostest.unitrun(
'pr2_calibration_executive', 
'test_chain_manager', TestChainManager)
   192     rostest.unitrun(
'pr2_calibration_executive', 
'test_laser_manager', TestLaserManager)
 
def callback(self, cam_id, msg)
def callback(self, cam_id, msg, interval_start, interval_end)
def callback(self, chain_id, msg)
def build_msg(type, secs)