Jim Ostrowski | 007e2ea | 2022-01-30 13:13:26 -0800 | [diff] [blame] | 1 | import copy |
| 2 | import glog |
| 3 | import json |
| 4 | import math |
| 5 | import numpy as np |
| 6 | import os |
| 7 | |
| 8 | glog.setLevel("INFO") |
| 9 | |
| 10 | |
| 11 | # Quick fix to naming games that happen with bazel |
| 12 | def bazel_name_fix(filename): |
| 13 | ret_name = filename |
| 14 | try: |
| 15 | from bazel_tools.tools.python.runfiles import runfiles |
| 16 | r = runfiles.Create() |
| 17 | ret_name = r.Rlocation('org_frc971/y2022/vision/' + filename) |
| 18 | #print("Trying directory: ", ret_name) |
| 19 | except: |
| 20 | print("Failed bazel_name_fix") |
| 21 | pass |
| 22 | |
| 23 | ### TODO<Jim>: Need to figure out why this isn't working |
| 24 | ### Hardcoding for now |
| 25 | if ret_name == None: |
| 26 | ret_name = '/home/jim/code/FRC/971-Robot-Code/y2022/vision/calib_files' |
| 27 | return ret_name |
| 28 | |
| 29 | |
| 30 | class CameraIntrinsics: |
| 31 | def __init__(self): |
| 32 | self.camera_matrix = [] |
| 33 | self.dist_coeffs = [] |
| 34 | |
| 35 | pass |
| 36 | |
| 37 | |
| 38 | class CameraExtrinsics: |
| 39 | def __init__(self): |
| 40 | self.R = [] |
| 41 | self.T = [] |
| 42 | |
| 43 | |
| 44 | class CameraParameters: |
| 45 | def __init__(self): |
| 46 | self.camera_int = CameraIntrinsics() |
| 47 | self.camera_ext = CameraExtrinsics() |
| 48 | self.turret_ext = None |
| 49 | self.node_name = "" |
| 50 | self.team_number = -1 |
| 51 | self.timestamp = 0 |
| 52 | |
| 53 | |
| 54 | def compute_extrinsic(camera_pitch, camera_yaw, T_camera, is_turret): |
| 55 | # Compute the extrinsic calibration based on pitch and translation |
| 56 | # Includes camera rotation from robot x,y,z to opencv (z, -x, -y) |
| 57 | |
| 58 | # Also, handle extrinsics for the turret |
| 59 | # The basic camera pose is relative to the center, base of the turret |
| 60 | # TODO<Jim>: Maybe store these to .json files, like with intrinsics? |
| 61 | base_cam_ext = CameraExtrinsics() |
| 62 | turret_cam_ext = CameraExtrinsics() |
| 63 | |
| 64 | camera_pitch_matrix = np.array( |
| 65 | [[np.cos(camera_pitch), 0.0, |
| 66 | np.sin(camera_pitch)], [0.0, 1.0, 0.0], |
| 67 | [-np.sin(camera_pitch), 0.0, |
| 68 | np.cos(camera_pitch)]]) |
| 69 | |
| 70 | camera_yaw_matrix = np.array( |
| 71 | [[np.cos(camera_yaw), -np.sin(camera_yaw), 0.0], |
| 72 | [np.sin(camera_yaw), np.cos(camera_yaw), 0.0], [0.0, 0.0, 1.0]]) |
| 73 | |
| 74 | robot_to_camera_rotation = np.array([[0., 0., 1.], [-1, 0, 0], [0, -1., |
| 75 | 0]]) |
| 76 | |
| 77 | if is_turret: |
| 78 | # Turret camera has default heading 180 deg away from the robot x |
| 79 | base_cam_ext.R = np.array([[-1.0, 0.0, 0.0], [0.0, -1.0, 0.0], |
| 80 | [0.0, 0.0, 1.0]]) |
| 81 | base_cam_ext.T = np.array([0.0, 0.0, 0.0]) |
| 82 | turret_cam_ext.R = camera_yaw_matrix @ camera_pitch_matrix @ robot_to_camera_rotation |
| 83 | turret_cam_ext.T = T_camera |
| 84 | else: |
| 85 | base_cam_ext.R = camera_yaw_matrix @ camera_pitch_matrix @ robot_to_camera_rotation |
| 86 | base_cam_ext.T = T_camera |
| 87 | turret_cam_ext = None |
| 88 | |
| 89 | return base_cam_ext, turret_cam_ext |
| 90 | |
| 91 | |
| 92 | def compute_extrinsic_by_pi(pi_number): |
| 93 | # Defaults for non-turret camera |
| 94 | camera_pitch = -20.0 * np.pi / 180.0 |
| 95 | camera_yaw = 0.0 |
| 96 | is_turret = False |
| 97 | # Default camera location to robot origin |
| 98 | T = np.array([0.0, 0.0, 0.0]) |
| 99 | |
| 100 | if pi_number == "pi1": |
| 101 | # This is the turret camera |
| 102 | camera_pitch = -10.0 * np.pi / 180.0 |
| 103 | is_turret = True |
| 104 | T = np.array([7.5 * 0.0254, -5.5 * 0.0254, 41.0 * 0.0254]) |
| 105 | elif pi_number == "pi2": |
| 106 | T = np.array([4.5 * 0.0254, 3.75 * 0.0254, 26.0 * 0.0254]) |
| 107 | elif pi_number == "pi3": |
| 108 | camera_yaw = 90.0 * np.pi / 180.0 |
| 109 | T = np.array([-2.75 * 0.0254, 5.25 * 0.0254, 25.25 * 0.0254]) |
| 110 | elif pi_number == "pi4": |
| 111 | camera_yaw = -90.0 * np.pi / 180.0 |
| 112 | T = np.array([-2.75 * 0.0254, -6 * 0.0254, 26 * 0.0254]) |
| 113 | elif pi_number == "pi5": |
| 114 | camera_yaw = 180.0 * np.pi / 180.0 |
| 115 | T = np.array([-7.25 * 0.0254, -4.24 * 0.0254, 16.5 * 0.0254]) |
| 116 | |
| 117 | return compute_extrinsic(camera_pitch, camera_yaw, T, is_turret) |
| 118 | |
| 119 | |
| 120 | def load_camera_definitions(): |
| 121 | ### CAMERA DEFINITIONS |
| 122 | # We only load in cameras that have a calibration file |
| 123 | # These are stored in y2022/vision/calib_files |
| 124 | # |
| 125 | # Or better yet, use //y2020/vision:calibration to calibrate the camera |
| 126 | # using a Charuco target board |
| 127 | |
| 128 | camera_list = [] |
| 129 | |
| 130 | dir_name = bazel_name_fix('calib_files') |
| 131 | if dir_name is not None: |
| 132 | glog.debug("Searching for calibration files in " + dir_name) |
| 133 | else: |
| 134 | glog.fatal("Failed to find calib_files directory") |
| 135 | |
| 136 | for filename in sorted(os.listdir(dir_name)): |
| 137 | glog.debug("Inspecting %s", filename) |
| 138 | if ("cam-calib-int" in filename |
| 139 | or 'calibration' in filename) and filename.endswith(".json"): |
| 140 | |
| 141 | # Extract intrinsics from file |
| 142 | calib_file = open(dir_name + "/" + filename, 'r') |
| 143 | calib_dict = json.loads(calib_file.read()) |
| 144 | |
| 145 | team_number = calib_dict["team_number"] |
| 146 | node_name = calib_dict["node_name"] |
| 147 | camera_matrix = np.asarray(calib_dict["intrinsics"]).reshape( |
| 148 | (3, 3)) |
| 149 | dist_coeffs = np.asarray(calib_dict["dist_coeffs"]).reshape((1, 5)) |
| 150 | |
| 151 | glog.debug("Found calib for " + node_name + ", team #" + |
| 152 | str(team_number)) |
| 153 | |
| 154 | camera_params = CameraParameters() |
| 155 | # TODO: Need to add reading in extrinsic camera parameters from json |
| 156 | camera_params.camera_ext, camera_params.turret_ext = compute_extrinsic_by_pi( |
| 157 | node_name) |
| 158 | |
| 159 | camera_params.node_name = node_name |
| 160 | camera_params.team_number = team_number |
| 161 | camera_params.camera_int.camera_matrix = copy.copy(camera_matrix) |
| 162 | camera_params.camera_int.dist_coeffs = copy.copy(dist_coeffs) |
| 163 | camera_list.append(camera_params) |
| 164 | |
| 165 | return camera_list |