Skip to content

Commit b918bef

Browse files
committed
Fixing Python format
1 parent 8d20df2 commit b918bef

File tree

1 file changed

+41
-41
lines changed

1 file changed

+41
-41
lines changed

yolo_ros/yolo_ros/detect_3d_node.py

Lines changed: 41 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -302,21 +302,21 @@ def compute_depth_bounds(depth_values: np.ndarray) -> Tuple[float, float, float]
302302
# Basic input validation
303303
if not isinstance(depth_values, np.ndarray):
304304
return 0.0, 0.0, 0.0
305-
305+
306306
if len(depth_values) == 0:
307307
return 0.0, 0.0, 0.0
308-
308+
309309
# Ensure all values are numeric and finite
310310
try:
311311
depth_values = np.asarray(depth_values, dtype=np.float64)
312312
valid_mask = np.isfinite(depth_values) & (depth_values > 0)
313313
depth_values = depth_values[valid_mask]
314314
except (ValueError, TypeError):
315315
return 0.0, 0.0, 0.0
316-
316+
317317
if len(depth_values) == 0:
318318
return 0.0, 0.0, 0.0
319-
319+
320320
if len(depth_values) < 4:
321321
z_center = float(np.median(depth_values))
322322
return z_center, float(np.min(depth_values)), float(np.max(depth_values))
@@ -526,7 +526,7 @@ def convert_bb_to_3d(
526526
# Basic input validations
527527
if depth_image is None or not isinstance(depth_image, np.ndarray):
528528
return None
529-
529+
530530
if depth_image.size == 0:
531531
return None
532532

@@ -565,23 +565,23 @@ def convert_bb_to_3d(
565565
pixel_coords = np.column_stack([x_grid.flatten(), y_grid.flatten()])
566566

567567
roi = roi / self.depth_image_units_divisor # Convert to meters
568-
568+
569569
# Validate that division did not produce NaN or inf
570570
if not np.any(np.isfinite(roi)):
571571
return None
572-
572+
573573
if not np.any(roi):
574574
return None
575575

576576
# Extract valid depth values with their spatial positions
577577
valid_depths = roi.flatten()
578-
578+
579579
# Ensure correct numeric type
580580
try:
581581
valid_depths = np.asarray(valid_depths, dtype=np.float64)
582582
except (ValueError, TypeError):
583583
return None
584-
584+
585585
valid_mask = (valid_depths > 0) & np.isfinite(valid_depths)
586586
valid_depths = valid_depths[valid_mask]
587587
valid_coords = pixel_coords[valid_mask]
@@ -607,7 +607,7 @@ def convert_bb_to_3d(
607607
y_center, y_min, y_max = Detect3DNode._compute_height_bounds(
608608
valid_coords, valid_depths, spatial_weights, depth_info
609609
)
610-
610+
611611
# Validate results
612612
if not all(np.isfinite([y_center, y_min, y_max])):
613613
return None
@@ -616,7 +616,7 @@ def convert_bb_to_3d(
616616
x_center, x_min, x_max = Detect3DNode._compute_width_bounds(
617617
valid_coords, valid_depths, spatial_weights, depth_info
618618
)
619-
619+
620620
# Validate results
621621
if not all(np.isfinite([x_center, x_min, x_max])):
622622
return None
@@ -696,47 +696,47 @@ def _compute_height_bounds(
696696
spatial_weights = np.asarray(spatial_weights, dtype=np.float64)
697697
except (ValueError, TypeError):
698698
return 0.0, 0.0, 0.0
699-
699+
700700
if len(valid_coords) == 0 or len(valid_depths) == 0:
701701
return 0.0, 0.0, 0.0
702-
702+
703703
if len(valid_coords) < 4:
704704
# Fallback: just use simple projection
705705
k = depth_info.k
706706
py, fy = k[5], k[4]
707-
707+
708708
# Validate camera parameters
709709
if fy == 0:
710710
return 0.0, 0.0, 0.0
711-
711+
712712
# Validate depths are finite
713713
if not np.all(np.isfinite(valid_depths)):
714714
return 0.0, 0.0, 0.0
715-
715+
716716
y_coords_pixel = valid_coords[:, 1]
717717
y_3d = valid_depths * (y_coords_pixel - py) / fy
718-
718+
719719
# Validate result
720720
if not np.all(np.isfinite(y_3d)):
721721
return 0.0, 0.0, 0.0
722-
722+
723723
return float(np.median(y_3d)), float(np.min(y_3d)), float(np.max(y_3d))
724724

725725
# Convert pixel coordinates to 3D y-coordinates
726726
k = depth_info.k
727727
py, fy = k[5], k[4]
728-
728+
729729
# Validate camera parameters
730730
if fy == 0:
731731
return 0.0, 0.0, 0.0
732-
732+
733733
# Validate depths are finite before calculation
734734
if not np.all(np.isfinite(valid_depths)):
735735
return 0.0, 0.0, 0.0
736-
736+
737737
y_coords_pixel = valid_coords[:, 1]
738738
y_3d = valid_depths * (y_coords_pixel - py) / fy
739-
739+
740740
# Validate result
741741
if not np.any(np.isfinite(y_3d)):
742742
return 0.0, 0.0, 0.0
@@ -837,47 +837,47 @@ def _compute_width_bounds(
837837
spatial_weights = np.asarray(spatial_weights, dtype=np.float64)
838838
except (ValueError, TypeError):
839839
return 0.0, 0.0, 0.0
840-
840+
841841
if len(valid_coords) == 0 or len(valid_depths) == 0:
842842
return 0.0, 0.0, 0.0
843-
843+
844844
if len(valid_coords) < 4:
845845
# Fallback: just use simple projection
846846
k = depth_info.k
847847
px, fx = k[2], k[0]
848-
848+
849849
# Validate camera parameters
850850
if fx == 0:
851851
return 0.0, 0.0, 0.0
852-
852+
853853
# Validate depths are finite
854854
if not np.all(np.isfinite(valid_depths)):
855855
return 0.0, 0.0, 0.0
856-
856+
857857
x_coords_pixel = valid_coords[:, 0]
858858
x_3d = valid_depths * (x_coords_pixel - px) / fx
859-
859+
860860
# Validate result
861861
if not np.all(np.isfinite(x_3d)):
862862
return 0.0, 0.0, 0.0
863-
863+
864864
return float(np.median(x_3d)), float(np.min(x_3d)), float(np.max(x_3d))
865865

866866
# Convert pixel coordinates to 3D x-coordinates
867867
k = depth_info.k
868868
px, fx = k[2], k[0]
869-
869+
870870
# Validate camera parameters
871871
if fx == 0:
872872
return 0.0, 0.0, 0.0
873-
873+
874874
# Validate depths are finite before calculation
875875
if not np.all(np.isfinite(valid_depths)):
876876
return 0.0, 0.0, 0.0
877-
877+
878878
x_coords_pixel = valid_coords[:, 0]
879879
x_3d = valid_depths * (x_coords_pixel - px) / fx
880-
880+
881881
# Validate result
882882
if not np.any(np.isfinite(x_3d)):
883883
return 0.0, 0.0, 0.0
@@ -979,18 +979,18 @@ def _compute_depth_bounds_weighted(
979979
spatial_weights = np.asarray(spatial_weights, dtype=np.float64)
980980
except (ValueError, TypeError):
981981
return 0.0, 0.0, 0.0
982-
982+
983983
if len(depth_values) == 0:
984984
return 0.0, 0.0, 0.0
985-
985+
986986
# Validate that all values are finite
987987
valid_mask = np.isfinite(depth_values) & np.isfinite(spatial_weights)
988988
depth_values = depth_values[valid_mask]
989989
spatial_weights = spatial_weights[valid_mask]
990-
990+
991991
if len(depth_values) == 0:
992992
return 0.0, 0.0, 0.0
993-
993+
994994
if len(depth_values) < 4:
995995
z_center = float(np.median(depth_values))
996996
return z_center, float(np.min(depth_values)), float(np.max(depth_values))
@@ -1155,20 +1155,20 @@ def convert_keypoints_to_3d(
11551155

11561156
# Sample depth image and project to 3D
11571157
z = depth_image[u, v]
1158-
1158+
11591159
# Validate and convert to float
11601160
try:
11611161
z = np.asarray(z, dtype=np.float64)
11621162
except (ValueError, TypeError):
11631163
return KeyPoint3DArray()
1164-
1164+
11651165
k = depth_info.k
11661166
px, py, fx, fy = k[2], k[5], k[0], k[4]
1167-
1167+
11681168
# Validate camera parameters
11691169
if fx == 0 or fy == 0:
11701170
return KeyPoint3DArray()
1171-
1171+
11721172
x = z * (v - px) / fx
11731173
y = z * (u - py) / fy
11741174
points_3d = (

0 commit comments

Comments
 (0)