def writeFiles(self, outDir, writeLabels = True): dir_tools.mkdir_ask(outDir) if writeLabels: ann.MultiLabeler.writeFiles(self,outDir) with open(os.path.join(outDir,"classifier.pkl"),"w") as fh: cPickle.dump(self.cls, fh) np.savetxt(os.path.join(outDir,"coeffs.txt"),self.cls.classifier.coef_) np.savetxt(os.path.join(outDir,"intercepts.txt"),self.cls.classifier.intercept_)
def writeFiles(self, outDir): dir_tools.mkdir_ask(outDir) for (i,image) in enumerate(self.images): outFile = "%s.label.png"%os.path.basename(self.imageFiles[i]) cv2.imwrite(os.path.join(outDir,outFile),self.labels[i]) with open(os.path.join(outDir,"label_info.json"),"w") as fh: json.dump( dict([(i, "LABEL_DESCRIPTION") for i in xrange(self.labelWindow.maxLabel)]), fh) print "wrote files to",outDir
#!/usr/bin/env python import argparse, dir_tools parser = argparse.ArgumentParser() parser.add_argument("outdir") args = parser.parse_args() dir_tools.mkdir_ask(args.outdir) import roslib roslib.load_manifest('brett_pr2') roslib.load_manifest('brett_utils') import rospy from brett_pr2.pr2 import PR2 from brett_utils.msg_utils import image2numpy from brett_utils.shell_hax import rospack_find import numpy as np from time import sleep, time import freenect import sensor_msgs.msg as sm from os.path import join import cPickle import cv2 rospy.init_node('record_calibration_images', disable_signals=True) joints = np.loadtxt("calibration_joints.txt") BRETT = PR2() BRETT.rgrip.close(max_effort=-1) BRETT.head.set_pan_tilt(0, .25)
#!/usr/bin/env python import argparse, dir_tools parser = argparse.ArgumentParser() parser.add_argument("outdir") args = parser.parse_args() dir_tools.mkdir_ask(args.outdir) import roslib roslib.load_manifest('brett_pr2') roslib.load_manifest('brett_utils') import rospy from brett_pr2.pr2 import PR2 from brett_utils.msg_utils import image2numpy from brett_utils.shell_hax import rospack_find import numpy as np from time import sleep, time import freenect import sensor_msgs.msg as sm from os.path import join import cPickle import cv2 rospy.init_node('record_calibration_images',disable_signals = True) joints = np.loadtxt("calibration_joints.txt") BRETT = PR2() BRETT.rgrip.close(max_effort=-1)