Skip to content

Commit

Permalink
Merge pull request #39 from open-dynamic-robot-initiative/fkloss/blac…
Browse files Browse the repository at this point in the history
…k_line_length

style: Use black's default line length (88 characters)
  • Loading branch information
luator authored Aug 7, 2024
2 parents b0c0411 + 5d84895 commit 51bd9ff
Show file tree
Hide file tree
Showing 15 changed files with 49 additions and 140 deletions.
4 changes: 1 addition & 3 deletions demos/demo_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,7 @@ def main() -> int:

try:
if args.pylon:
camera_driver = trifinger_cameras.camera.PylonDriver(
args.camera_id
)
camera_driver = trifinger_cameras.camera.PylonDriver(args.camera_id)
else:
camera_id = int(args.camera_id) if args.camera_id else 0
camera_driver = trifinger_cameras.camera.OpenCVDriver(camera_id)
Expand Down
8 changes: 2 additions & 6 deletions demos/demo_tricamera.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,10 @@ def main() -> None: # noqa: D103
camera_names = ["camera60", "camera180", "camera300"]

if args.multi_process:
camera_data = trifinger_cameras.tricamera.MultiProcessData(
"tricamera", False
)
camera_data = trifinger_cameras.tricamera.MultiProcessData("tricamera", False)
else:
camera_data = trifinger_cameras.tricamera.SingleProcessData()
camera_driver = trifinger_cameras.tricamera.TriCameraDriver(
*camera_names
)
camera_driver = trifinger_cameras.tricamera.TriCameraDriver(*camera_names)
camera_backend = trifinger_cameras.tricamera.Backend( # noqa: F841
camera_driver, camera_data
)
Expand Down
3 changes: 0 additions & 3 deletions pyproject.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,3 @@
[tool.black]
line-length = 79

[tool.pylint.messages_control]
disable = "C0330, C0326"

Expand Down
20 changes: 5 additions & 15 deletions python/trifinger_cameras/charuco_board_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -159,9 +159,7 @@ def visualize_board(
debug_image = image

if charuco_ids is not None:
debug_image = cv2.aruco.drawDetectedCornersCharuco(
image, charuco_corners
)
debug_image = cv2.aruco.drawDetectedCornersCharuco(image, charuco_corners)

if rvec is not None and tvec is not None:
debug_image = cv2.aruco.drawAxis(
Expand Down Expand Up @@ -194,9 +192,7 @@ def detect_board_in_camera_stream(self, device=0):
ret, frame = cap.read()

charuco_corners, charuco_ids, rvec, tvec = self.detect_board(frame)
if self.visualize_board(
frame, charuco_corners, charuco_ids, rvec, tvec, 1
):
if self.visualize_board(frame, charuco_corners, charuco_ids, rvec, tvec, 1):
break

# When everything done, release the capture
Expand Down Expand Up @@ -235,9 +231,7 @@ def detect_board_in_image(self, filename, visualize=False):
charuco_corners, charuco_ids, rvec, tvec = self.detect_board(img)
if charuco_ids is not None:
if visualize:
self.visualize_board(
img, charuco_corners, charuco_ids, rvec, tvec, 0
)
self.visualize_board(img, charuco_corners, charuco_ids, rvec, tvec, 0)

if rvec is not None:
print(json.dumps({"rvec": rvec.tolist(), "tvec": tvec.tolist()}))
Expand All @@ -246,9 +240,7 @@ def detect_board_in_image(self, filename, visualize=False):

return rvec, tvec

def detect_board_in_files(
self, files: typing.List[str], visualize: bool = False
):
def detect_board_in_files(self, files: typing.List[str], visualize: bool = False):
"""Detect the board in multiple files.
Tries to detect the Charuco board in the given list of image files.
Expand Down Expand Up @@ -312,9 +304,7 @@ def calibrate(
self.camera_matrix = None
self.dist_coeffs = None

all_corners, all_ids, image_size = self.detect_board_in_files(
files, visualize
)
all_corners, all_ids, image_size = self.detect_board_in_files(files, visualize)

camera_matrix = np.zeros((3, 3))
dist_coeffs = np.zeros(4)
Expand Down
7 changes: 1 addition & 6 deletions scripts/analyze_tricamera_log.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,7 @@ def main():
print("Total duration: {:.1f} seconds".format(duration))

stamps = [
np.array(
[
observation.cameras[c].timestamp
for observation in log_reader.data
]
)
np.array([observation.cameras[c].timestamp for observation in log_reader.data])
for c in range(3)
]

Expand Down
47 changes: 13 additions & 34 deletions scripts/calibrate_cameras.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,7 @@ def calibrate_intrinsic_parameters(calibration_data, calibration_results_file):

pattern = os.path.join(calibration_data, "*.png")
files = glob.glob(pattern)
camera_matrix, dist_coeffs, error = handler.calibrate(
files, visualize=True
)
camera_matrix, dist_coeffs, error = handler.calibrate(files, visualize=True)
camera_info = dict()
camera_info["camera_matrix"] = dict()
camera_info["camera_matrix"]["rows"] = 3
Expand All @@ -47,9 +45,7 @@ def calibrate_intrinsic_parameters(calibration_data, calibration_results_file):
camera_info["distortion_coefficients"] = dict()
camera_info["distortion_coefficients"]["rows"] = 1
camera_info["distortion_coefficients"]["cols"] = 5
camera_info["distortion_coefficients"][
"data"
] = dist_coeffs.flatten().tolist()
camera_info["distortion_coefficients"]["data"] = dist_coeffs.flatten().tolist()

with open(calibration_results_file, "w") as outfile:
yaml.dump(
Expand Down Expand Up @@ -111,9 +107,7 @@ def config_matrix(data):
calibration_data["projection_matrix"] = dict()
calibration_data["projection_matrix"]["rows"] = 4
calibration_data["projection_matrix"]["cols"] = 4
calibration_data["projection_matrix"][
"data"
] = projection_matrix.flatten().tolist()
calibration_data["projection_matrix"]["data"] = projection_matrix.flatten().tolist()

with open(extrinsic_calibration_filename, "w") as outfile:
yaml.dump(
Expand Down Expand Up @@ -258,9 +252,7 @@ def calibrate_mean_extrinsic_parameters(
# x-distance of the pattern origin to the world origin
tx = Dx - dx
# y-distance of the pattern origin to the world origin
ty = (Dy - T2 * np.sin(alphr) - T1 * np.tan(alphr)) * np.cos(
alphr
) - dy
ty = (Dy - T2 * np.sin(alphr) - T1 * np.tan(alphr)) * np.cos(alphr) - dy
# z-distance of the pattern origin to the world origin
tz = (
T2
Expand All @@ -283,9 +275,9 @@ def calibrate_mean_extrinsic_parameters(

# absolute world vectors equivalent to cv2 tvec and rvec:
tvecW = np.matmul(cv2.Rodrigues(rvec)[0], Tvec) + tvec.T
rvecW = cv2.Rodrigues(
np.matmul(cv2.Rodrigues(rvec)[0], np.matmul(zMat, xMat))
)[0]
rvecW = cv2.Rodrigues(np.matmul(cv2.Rodrigues(rvec)[0], np.matmul(zMat, xMat)))[
0
]
# embed()

projection_matrix[ind, 0:4, 0:4] = utils.rodrigues_to_matrix(rvecW)
Expand Down Expand Up @@ -406,22 +398,16 @@ def calibrate_mean_extrinsic_parameters(
calibration_data["camera_matrix"] = dict()
calibration_data["camera_matrix"]["rows"] = 3
calibration_data["camera_matrix"]["cols"] = 3
calibration_data["camera_matrix"][
"data"
] = camera_matrix.flatten().tolist()
calibration_data["camera_matrix"]["data"] = camera_matrix.flatten().tolist()
calibration_data["distortion_coefficients"] = dict()
calibration_data["distortion_coefficients"]["rows"] = 1
calibration_data["distortion_coefficients"]["cols"] = 5
calibration_data["distortion_coefficients"][
"data"
] = dist_coeffs.flatten().tolist()
calibration_data["distortion_coefficients"]["data"] = dist_coeffs.flatten().tolist()

calibration_data["projection_matrix"] = dict()
calibration_data["projection_matrix"]["rows"] = 4
calibration_data["projection_matrix"]["cols"] = 4
calibration_data["projection_matrix"][
"data"
] = projection_matrix.flatten().tolist()
calibration_data["projection_matrix"]["data"] = projection_matrix.flatten().tolist()

calibration_data["projection_matrix_std"] = dict()
calibration_data["projection_matrix_std"]["rows"] = 4
Expand Down Expand Up @@ -502,10 +488,7 @@ def main():
)

elif args.action == "extrinsic_mean":
if (
not args.calibration_data
and not args.intrinsic_calibration_filename
):
if not args.calibration_data and not args.intrinsic_calibration_filename:
raise RuntimeError(
"neither calibration_data nor intrinsic_calibration_filename not specified."
)
Expand All @@ -518,14 +501,10 @@ def main():
calibration_data = yaml.safe_load(file)

def config_matrix(data):
return np.array(data["data"]).reshape(
data["rows"], data["cols"]
)
return np.array(data["data"]).reshape(data["rows"], data["cols"])

camera_matrix = config_matrix(calibration_data["camera_matrix"])
dist_coeffs = config_matrix(
calibration_data["distortion_coefficients"]
)
dist_coeffs = config_matrix(calibration_data["distortion_coefficients"])
else:
camera_matrix, dist_coeffs = calibrate_intrinsic_parameters(
args.calibration_data, args.extrinsic_calibration_filename
Expand Down
22 changes: 7 additions & 15 deletions scripts/calibrate_trifingerpro_cameras.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,7 @@ def calibrate_intrinsic_parameters(
camera_info["distortion_coefficients"] = dict()
camera_info["distortion_coefficients"]["rows"] = 1
camera_info["distortion_coefficients"]["cols"] = 5
camera_info["distortion_coefficients"][
"data"
] = dist_coeffs.flatten().tolist()
camera_info["distortion_coefficients"]["data"] = dist_coeffs.flatten().tolist()

with open(calibration_results_file, "w") as outfile:
yaml.dump(
Expand Down Expand Up @@ -164,9 +162,7 @@ def calibrate_mean_extrinsic_parameters(
# x-distance of the pattern origin to the world origin
tx = Dx - dx
# y-distance of the pattern origin to the world origin
ty = (Dy - T2 * np.sin(alphr) - T1 * np.tan(alphr)) * np.cos(
alphr
) - dy
ty = (Dy - T2 * np.sin(alphr) - T1 * np.tan(alphr)) * np.cos(alphr) - dy
# z-distance of the pattern origin to the world origin
tz = (
T2
Expand All @@ -189,9 +185,9 @@ def calibrate_mean_extrinsic_parameters(

# absolute world vectors equivalent to cv2 tvec and rvec:
tvecW = np.matmul(cv2.Rodrigues(rvec)[0], Tvec) + tvec.T
rvecW = cv2.Rodrigues(
np.matmul(cv2.Rodrigues(rvec)[0], np.matmul(zMat, xMat))
)[0]
rvecW = cv2.Rodrigues(np.matmul(cv2.Rodrigues(rvec)[0], np.matmul(zMat, xMat)))[
0
]
# embed()

pose_matrix[ind, 0:4, 0:4] = utils.rodrigues_to_matrix(rvecW)
Expand Down Expand Up @@ -307,9 +303,7 @@ def calibrate_mean_extrinsic_parameters(
print("Std proj matrix:")
print(camera_params.tf_world_to_camera_std)
print("Rel std proj matrix:")
print(
camera_params.tf_world_to_camera_std / camera_params.tf_world_to_camera
)
print(camera_params.tf_world_to_camera_std / camera_params.tf_world_to_camera)

return camera_params

Expand Down Expand Up @@ -417,9 +411,7 @@ def config_matrix(data):
return np.array(data["data"]).reshape(data["rows"], data["cols"])

camera_matrix = config_matrix(calibration_data["camera_matrix"])
dist_coeffs = config_matrix(
calibration_data["distortion_coefficients"]
)
dist_coeffs = config_matrix(calibration_data["distortion_coefficients"])
else:
camera_matrix, dist_coeffs = calibrate_intrinsic_parameters(
image_files, output_file_full, args.visualize
Expand Down
15 changes: 4 additions & 11 deletions scripts/check_camera_sharpness.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,7 @@ def add_label(
return image


def auto_canny_params(
image: np.ndarray, sigma: float = 0.33
) -> tuple[float, float]:
def auto_canny_params(image: np.ndarray, sigma: float = 0.33) -> tuple[float, float]:
median = np.median(image)
lower = max(0, (1.0 - sigma) * median)
upper = min(255, (1.0 + sigma) * median)
Expand Down Expand Up @@ -152,19 +150,15 @@ def main() -> None:
max(200, params.canny_threshold1),
params.set_canny_threshold1,
)
cv2.setTrackbarPos(
"Canny threshold 1", window_name, int(params.canny_threshold1)
)
cv2.setTrackbarPos("Canny threshold 1", window_name, int(params.canny_threshold1))
cv2.createTrackbar(
"Canny threshold 2",
window_name,
0,
max(400, params.canny_threshold2),
params.set_canny_threshold2,
)
cv2.setTrackbarPos(
"Canny threshold 2", window_name, int(params.canny_threshold2)
)
cv2.setTrackbarPos("Canny threshold 2", window_name, int(params.canny_threshold2))
cv2.createTrackbar(
"Edge mean threshold",
window_name,
Expand Down Expand Up @@ -209,8 +203,7 @@ def main() -> None:
add_label(image, args.camera_id, "top")
add_label(
image,
"Canny mean: %.1f | smoothed: %.1f"
% (edges_mean, mean_buffer_mean),
"Canny mean: %.1f | smoothed: %.1f" % (edges_mean, mean_buffer_mean),
"bottom",
)

Expand Down
4 changes: 1 addition & 3 deletions scripts/detect_aruco_marker.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,7 @@

def main():
# ArUco stuff
marker_dict = cv2.aruco.getPredefinedDictionary(
cv2.aruco.DICT_APRILTAG_16h5
)
marker_dict = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_APRILTAG_16h5)

cap = cv2.VideoCapture(0)
while True:
Expand Down
11 changes: 3 additions & 8 deletions scripts/overlay_real_and_rendered_images.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,7 @@ def main():
finger.reset_finger_positions_and_velocities([-1.57, 1.57, -2.7] * 3)

# load real images
image_dir = (
args.image_dir if args.image_dir else args.config_dir[0] / "0001"
)
image_dir = args.image_dir if args.image_dir else args.config_dir[0] / "0001"
print("image_dir:", image_dir)
real_images = [
cv2.imread(str(image_dir / "camera60.png")),
Expand All @@ -94,8 +92,7 @@ def on_trackbar(val):
sim_images = cameras.get_images()
# images are rgb --> convert to bgr for opencv
sim_images = [
cv2.cvtColor(np.array(img), cv2.COLOR_RGB2BGR)
for img in sim_images
cv2.cvtColor(np.array(img), cv2.COLOR_RGB2BGR) for img in sim_images
]
sim_images = np.hstack(sim_images)

Expand All @@ -106,9 +103,7 @@ def on_trackbar(val):

cv2.namedWindow(title_window)
trackbar_name = "Alpha x %d" % SLIDER_MAX
cv2.createTrackbar(
trackbar_name, title_window, 0, SLIDER_MAX, on_trackbar
)
cv2.createTrackbar(trackbar_name, title_window, 0, SLIDER_MAX, on_trackbar)
# Show some stuff
blend.on_trackbar(0)

Expand Down
8 changes: 2 additions & 6 deletions scripts/record_image_dataset.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,9 +124,7 @@ def main():
camera_module = trifinger_cameras.camera
image_saver = SingleImageSaver(args.outdir, args.camera_id)
elif args.driver == "opencv":
camera_driver = trifinger_cameras.camera.OpenCVDriver(
int(args.camera_id)
)
camera_driver = trifinger_cameras.camera.OpenCVDriver(int(args.camera_id))
camera_module = trifinger_cameras.camera
image_saver = SingleImageSaver(args.outdir, args.camera_id)

Expand All @@ -147,9 +145,7 @@ def main():
observation = camera_frontend.get_latest_observation()
if args.driver == "tri":
for i, name in enumerate(camera_names):
image = utils.convert_image(
observation.cameras[i].image
)
image = utils.convert_image(observation.cameras[i].image)
cv2.imshow(name, image)
else:
image = utils.convert_image(observation.image)
Expand Down
12 changes: 3 additions & 9 deletions scripts/tricamera_log_viewer.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,9 @@ def main():
window_60 = "Image Stream camera60"
window_180 = "Image Stream camera180"
window_300 = "Image Stream camera300"
cv2.imshow(
window_60, utils.convert_image(observation.cameras[0].image)
)
cv2.imshow(
window_180, utils.convert_image(observation.cameras[1].image)
)
cv2.imshow(
window_300, utils.convert_image(observation.cameras[2].image)
)
cv2.imshow(window_60, utils.convert_image(observation.cameras[0].image))
cv2.imshow(window_180, utils.convert_image(observation.cameras[1].image))
cv2.imshow(window_300, utils.convert_image(observation.cameras[2].image))

# stop if either "q" or ESC is pressed
if cv2.waitKey(interval) in [ord("q"), 27]: # 27 = ESC
Expand Down
Loading

0 comments on commit 51bd9ff

Please sign in to comment.