def main(): from optparse import OptionParser, OptionGroup parser = OptionParser("%prog --size SIZE1 --square SQUARE1 [ --size SIZE2 --square SQUARE2 ]", description=None) parser.add_option("-c", "--camera_name", type="string", default='narrow_stereo', help="name of the camera to appear in the calibration file") group = OptionGroup(parser, "Chessboard Options", "You must specify one or more chessboards as pairs of --size and --square options.") group.add_option("-p", "--pattern", type="string", default="chessboard", help="calibration pattern to detect - 'chessboard', 'circles', 'acircles', 'charuco'\n" + " if 'charuco' is used, a --charuco_marker_size and --aruco_dict argument must be supplied\n" + " with each --size and --square argument") group.add_option("-s", "--size", action="append", default=[], help="chessboard size as NxM, counting interior corners (e.g. a standard chessboard is 7x7)") group.add_option("-q", "--square", action="append", default=[], help="chessboard square size in meters") group.add_option("-m", "--charuco_marker_size", action="append", default=[], help="ArUco marker size (meters); only valid with `-p charuco`") group.add_option("-d", "--aruco_dict", action="append", default=[], help="ArUco marker dictionary; only valid with `-p charuco`; one of 'aruco_orig', '4x4_250', " + "'5x5_250', '6x6_250', '7x7_250'") parser.add_option_group(group) group = OptionGroup(parser, "ROS Communication Options") group.add_option("--approximate", type="float", default=0.0, help="allow specified slop (in seconds) when pairing images from unsynchronized stereo cameras") group.add_option("--no-service-check", action="store_false", dest="service_check", default=True, help="disable check for set_camera_info services at startup") group.add_option("--queue-size", type="int", default=1, help="image queue size (default %default, set to 0 for unlimited)") parser.add_option_group(group) group = OptionGroup(parser, "Calibration Optimizer Options") group.add_option("--fix-principal-point", action="store_true", default=False, help="for pinhole, fix the principal point at the image center") group.add_option("--fix-aspect-ratio", action="store_true", default=False, help="for pinhole, enforce focal lengths (fx, fy) are equal") group.add_option("--zero-tangent-dist", action="store_true", default=False, help="for pinhole, set tangential distortion coefficients (p1, p2) to zero") group.add_option("-k", "--k-coefficients", type="int", default=2, metavar="NUM_COEFFS", help="for pinhole, number of radial distortion coefficients to use (up to 6, default %default)") group.add_option("--fisheye-recompute-extrinsicsts", action="store_true", default=False, help="for fisheye, extrinsic will be recomputed after each iteration of intrinsic optimization") group.add_option("--fisheye-fix-skew", action="store_true", default=False, help="for fisheye, skew coefficient (alpha) is set to zero and stay zero") group.add_option("--fisheye-fix-principal-point", action="store_true", default=False, help="for fisheye,fix the principal point at the image center") group.add_option("--fisheye-k-coefficients", type="int", default=4, metavar="NUM_COEFFS", help="for fisheye, number of radial distortion coefficients to use fixing to zero the rest (up to 4, default %default)") group.add_option("--fisheye-check-conditions", action="store_true", default=False, help="for fisheye, the functions will check validity of condition number") group.add_option("--disable_calib_cb_fast_check", action='store_true', default=False, help="uses the CALIB_CB_FAST_CHECK flag for findChessboardCorners") group.add_option("--max-chessboard-speed", type="float", default=-1.0, help="Do not use samples where the calibration pattern is moving faster \ than this speed in px/frame. Set to eg. 0.5 for rolling shutter cameras.") parser.add_option_group(group) options, args = parser.parse_args() if (len(options.size) != len(options.square)): parser.error("Number of size and square inputs must be the same!") if not options.square: options.square.append("0.108") options.size.append("8x6") boards = [] if options.pattern == "charuco" and optionsValidCharuco(options, parser): for (sz, sq, ms, ad) in zip(options.size, options.square, options.charuco_marker_size, options.aruco_dict): size = tuple([int(c) for c in sz.split('x')]) boards.append(ChessboardInfo('charuco', size[0], size[1], float(sq), float(ms), ad)) else: for (sz, sq) in zip(options.size, options.square): size = tuple([int(c) for c in sz.split('x')]) boards.append(ChessboardInfo(options.pattern, size[0], size[1], float(sq))) if options.approximate == 0.0: sync = message_filters.TimeSynchronizer else: sync = functools.partial(ApproximateTimeSynchronizer, slop=options.approximate) # Pinhole opencv calibration options parsing num_ks = options.k_coefficients calib_flags = 0 if options.fix_principal_point: calib_flags |= cv2.CALIB_FIX_PRINCIPAL_POINT if options.fix_aspect_ratio: calib_flags |= cv2.CALIB_FIX_ASPECT_RATIO if options.zero_tangent_dist: calib_flags |= cv2.CALIB_ZERO_TANGENT_DIST if (num_ks > 3): calib_flags |= cv2.CALIB_RATIONAL_MODEL if (num_ks < 6): calib_flags |= cv2.CALIB_FIX_K6 if (num_ks < 5): calib_flags |= cv2.CALIB_FIX_K5 if (num_ks < 4): calib_flags |= cv2.CALIB_FIX_K4 if (num_ks < 3): calib_flags |= cv2.CALIB_FIX_K3 if (num_ks < 2): calib_flags |= cv2.CALIB_FIX_K2 if (num_ks < 1): calib_flags |= cv2.CALIB_FIX_K1 # Opencv calibration flags parsing: num_ks = options.fisheye_k_coefficients fisheye_calib_flags = 0 if options.fisheye_fix_principal_point: fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_PRINCIPAL_POINT if options.fisheye_fix_skew: fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_SKEW if options.fisheye_recompute_extrinsicsts: fisheye_calib_flags |= cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC if options.fisheye_check_conditions: fisheye_calib_flags |= cv2.fisheye.CALIB_CHECK_COND if (num_ks < 4): fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K4 if (num_ks < 3): fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K3 if (num_ks < 2): fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K2 if (num_ks < 1): fisheye_calib_flags |= cv2.fisheye.CALIB_FIX_K1 pattern = Patterns.Chessboard if options.pattern == 'circles': pattern = Patterns.Circles elif options.pattern == 'acircles': pattern = Patterns.ACircles elif options.pattern == 'charuco': pattern = Patterns.ChArUco elif options.pattern != 'chessboard': print('Unrecognized pattern %s, defaulting to chessboard' % options.pattern) if options.disable_calib_cb_fast_check: checkerboard_flags = 0 else: checkerboard_flags = cv2.CALIB_CB_FAST_CHECK rospy.init_node('cameracalibrator') node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, fisheye_calib_flags, pattern, options.camera_name, checkerboard_flags=checkerboard_flags, max_chessboard_speed=options.max_chessboard_speed, queue_size=options.queue_size) rospy.spin()
def main(): from optparse import OptionParser, OptionGroup parser = OptionParser("%prog --size SIZE1 --square SQUARE1 [ --size SIZE2 --square SQUARE2 ]", description=None) parser.add_option("-c", "--camera_name", type="string", default='autoware_camera_calibration', help="name of the camera to appear in the calibration file") parser.add_option("-o", "--output", type="string", default="yaml", help="type of output - 'yaml' or 'tar'") parser.add_option("-d", "--detection", type="string", default="cv2", help="Chessboard detection algorithm, OpenCV2 or Matlab (python matlab engine) - 'cv2', 'matlab'") group = OptionGroup(parser, "Chessboard Options", "You must specify one or more chessboards as pairs of --size and --square options.") group.add_option("-p", "--pattern", type="string", default="chessboard", help="calibration pattern to detect - 'chessboard', 'circles', 'acircles'") group.add_option("-s", "--size", action="append", default=[], help="chessboard size as NxM, counting interior corners (e.g. a standard chessboard is 7x7)") group.add_option("-q", "--square", action="append", default=[], help="chessboard square size in meters") group.add_option("--min_samples", type="int", default=40, help="defines the minimum number of samples before allowing to calibrate regardless of the status") parser.add_option_group(group) group = OptionGroup(parser, "ROS Communication Options") group.add_option("--approximate", type="float", default=0.0, help="allow specified slop (in seconds) when pairing images from unsynchronized stereo cameras") group.add_option("--no-service-check", action="store_false", dest="service_check", default=True, help="disable check for set_camera_info services at startup") parser.add_option_group(group) group = OptionGroup(parser, "Calibration Optimizer Options") group.add_option("--fix-principal-point", action="store_true", default=False, help="fix the principal point at the image center") group.add_option("--fix-aspect-ratio", action="store_true", default=False, help="enforce focal lengths (fx, fy) are equal") group.add_option("--zero-tangent-dist", action="store_true", default=False, help="set tangential distortion coefficients (p1, p2) to zero") group.add_option("-k", "--k-coefficients", type="int", default=3, metavar="NUM_COEFFS", help="number of radial distortion coefficients to use (up to 6, default %default)") group.add_option("--disable_calib_cb_fast_check", action='store_true', default=False, help="uses the CALIB_CB_FAST_CHECK flag for findChessboardCorners") parser.add_option_group(group) options, args = parser.parse_args() if len(options.size) != len(options.square): parser.error("Number of size and square inputs must be the same!") if options.detection == "cv2": print('Using OpenCV 2 for chessboard corner detection') elif options.detection == "matlab": print('Using matlab for chessboard corner detection') else: print('Unrecognized detection method %s, defaulting to OpenCV 2' % options.detection) options.detection = "cv2" if options.output == "yaml": print('Saving as autoware yaml') elif options.output == "tar": print('Saving as tar') else: print('Unrecognized output method %s, defaulting to Autoware Yaml' % options.output) options.output = "yaml" if not options.square: options.square.append("0.108") options.size.append("8x6") boards = [] for (sz, sq) in zip(options.size, options.square): size = tuple([int(c) for c in sz.split('x')]) boards.append(ChessboardInfo(size[0], size[1], float(sq))) if options.approximate == 0.0: sync = message_filters.TimeSynchronizer else: sync = functools.partial(ApproximateTimeSynchronizer, slop=options.approximate) num_ks = options.k_coefficients calib_flags = 0 if options.fix_principal_point: calib_flags |= cv2.CALIB_FIX_PRINCIPAL_POINT if options.fix_aspect_ratio: calib_flags |= cv2.CALIB_FIX_ASPECT_RATIO if options.zero_tangent_dist: calib_flags |= cv2.CALIB_ZERO_TANGENT_DIST if (num_ks > 3): calib_flags |= cv2.CALIB_RATIONAL_MODEL if (num_ks < 6): calib_flags |= cv2.CALIB_FIX_K6 if (num_ks < 5): calib_flags |= cv2.CALIB_FIX_K5 if (num_ks < 4): calib_flags |= cv2.CALIB_FIX_K4 if (num_ks < 3): calib_flags |= cv2.CALIB_FIX_K3 if (num_ks < 2): calib_flags |= cv2.CALIB_FIX_K2 if (num_ks < 1): calib_flags |= cv2.CALIB_FIX_K1 pattern = Patterns.Chessboard if options.pattern == 'circles': pattern = Patterns.Circles elif options.pattern == 'acircles': pattern = Patterns.ACircles elif options.pattern != 'chessboard': print('Unrecognized pattern %s, defaulting to chessboard' % options.pattern) if options.disable_calib_cb_fast_check: checkerboard_flags = 0 else: checkerboard_flags = cv2.CALIB_CB_FAST_CHECK rospy.init_node('cameracalibrator') node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, pattern, options.camera_name, options.detection, options.output, min_good_enough=options.min_samples, checkerboard_flags=checkerboard_flags) rospy.spin()
def main(args=None): from optparse import OptionParser, OptionGroup parser = OptionParser( "%prog --size SIZE1 --square SQUARE1 [ --size SIZE2 --square SQUARE2 ]", description=None) parser.add_option( "-c", "--camera_name", type="string", default='narrow_stereo', help="name of the camera to appear in the calibration file") parser.add_option( "--image", type="string", default='image', help="name of the image topic to appear in the calibration file") parser.add_option( "--camera", type="string", default='camera', help="name of the camera topic to appear in the calibration file") parser.add_option( "--left_camera", type="string", default='left_camera', help="name of the left camera to appear in the calibration file") parser.add_option( "--right_camera", type="string", default='right_camera', help="name of the right camera to appear in the calibration file") group = OptionGroup( parser, "Chessboard Options", "You must specify one or more chessboards as pairs of --size and --square options." ) group.add_option( "-p", "--pattern", type="string", default="chessboard", help= "calibration pattern to detect - 'chessboard', 'circles', 'acircles'") group.add_option( "-s", "--size", action="append", default=[], help= "chessboard size as NxM, counting interior corners (e.g. a standard chessboard is 7x7)" ) group.add_option("-q", "--square", action="append", default=[], help="chessboard square size in meters") parser.add_option_group(group) group = OptionGroup(parser, "ROS Communication Options") group.add_option( "--approximate", type="float", default=0.0, help= "allow specified slop (in seconds) when pairing images from unsynchronized stereo cameras" ) group.add_option( "--no-service-check", action="store_false", dest="service_check", default=False, help="disable check for set_camera_info services at startup") parser.add_option_group(group) group = OptionGroup(parser, "Calibration Optimizer Options") group.add_option("--fix-principal-point", action="store_true", default=False, help="fix the principal point at the image center") group.add_option("--fix-aspect-ratio", action="store_true", default=False, help="enforce focal lengths (fx, fy) are equal") group.add_option( "--zero-tangent-dist", action="store_true", default=False, help="set tangential distortion coefficients (p1, p2) to zero") group.add_option( "-k", "--k-coefficients", type="int", default=2, metavar="NUM_COEFFS", help= "number of radial distortion coefficients to use (up to 6, default %default)" ) group.add_option( "--disable_calib_cb_fast_check", action='store_true', default=False, help="uses the CALIB_CB_FAST_CHECK flag for findChessboardCorners") parser.add_option_group(group) options, args = parser.parse_args() if len(options.size) != len(options.square): parser.error("Number of size and square inputs must be the same!") if not options.square: options.square.append("0.108") options.size.append("8x6") boards = [] for (sz, sq) in zip(options.size, options.square): size = tuple([int(c) for c in sz.split('x')]) boards.append(ChessboardInfo(size[0], size[1], float(sq))) if options.approximate == 0.0: sync = message_filters.TimeSynchronizer else: sync = functools.partial(ApproximateTimeSynchronizer, slop=options.approximate) num_ks = options.k_coefficients calib_flags = 0 if options.fix_principal_point: calib_flags |= cv2.CALIB_FIX_PRINCIPAL_POINT if options.fix_aspect_ratio: calib_flags |= cv2.CALIB_FIX_ASPECT_RATIO if options.zero_tangent_dist: calib_flags |= cv2.CALIB_ZERO_TANGENT_DIST if (num_ks > 3): calib_flags |= cv2.CALIB_RATIONAL_MODEL if (num_ks < 6): calib_flags |= cv2.CALIB_FIX_K6 if (num_ks < 5): calib_flags |= cv2.CALIB_FIX_K5 if (num_ks < 4): calib_flags |= cv2.CALIB_FIX_K4 if (num_ks < 3): calib_flags |= cv2.CALIB_FIX_K3 if (num_ks < 2): calib_flags |= cv2.CALIB_FIX_K2 if (num_ks < 1): calib_flags |= cv2.CALIB_FIX_K1 pattern = Patterns.Chessboard if options.pattern == 'circles': pattern = Patterns.Circles elif options.pattern == 'acircles': pattern = Patterns.ACircles elif options.pattern != 'chessboard': print('Unrecognized pattern %s, defaulting to chessboard' % options.pattern) if options.disable_calib_cb_fast_check: checkerboard_flags = 0 else: checkerboard_flags = cv2.CALIB_CB_FAST_CHECK rclpy.init(args=args) node = OpenCVCalibrationNode(boards, options.service_check, sync, calib_flags, pattern, camera_name=options.camera_name, camera=options.camera, left_camera=options.left_camera, right_camera=options.right_camera, image=options.image, checkerboard_flags=checkerboard_flags) rclpy.spin(node) node.destroy_node() rclpy.shutdown()