Skip to content

Commit 41bc51e

Browse files
new lint fix (#26)
* new lint fix * Fix code style issues with clang_format * Fix code style issues with clang_format --------- Co-authored-by: WATonomousAdmin <admin@watonomous.ca>
1 parent 5b8613d commit 41bc51e

File tree

83 files changed

+19989
-20149
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

83 files changed

+19989
-20149
lines changed

.github/workflows/linting_auto.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ jobs:
2626
- name: Set up Python
2727
uses: actions/setup-python@v1
2828
with:
29-
python-version: '3.10.18'
29+
python-version: '3.10.19'
3030

3131
- name: Install Python dependencies
3232
run: pip install autopep8 clang-format

autonomy/behaviour/octo_map/launch/octo_map.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,4 +10,4 @@ def generate_launch_description():
1010
executable='octo_map_node',
1111
output='screen',
1212
emulate_tty=True),
13-
])
13+
])

autonomy/behaviour/octo_map/octo_map/octo_map_node.py

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,11 @@
1010
from std_msgs.msg import Header
1111
import sensor_msgs_py.point_cloud2 as pc2
1212

13+
1314
class OctoMapNode(Node):
1415
def __init__(self):
1516
super().__init__('octo_map_node')
16-
17+
1718
# Subscribe to processed perception data
1819
self.rgb_sub = self.create_subscription(
1920
Image, '/perception/rgb_processed', self.rgb_callback, 10)
@@ -22,18 +23,19 @@ def __init__(self):
2223
self.info_sub = self.create_subscription(
2324
CameraInfo, '/perception/camera_info', self.info_callback, 10)
2425

25-
self.octo_pub = self.create_publisher(PointCloud2, '/behaviour/octo_map', 10)
26-
26+
self.octo_pub = self.create_publisher(
27+
PointCloud2, '/behaviour/octo_map', 10)
28+
2729
self.rgb_image = None
2830
self.depth_image = None
2931
self.bridge = CvBridge()
30-
32+
3133
# Camera intrinsics (will be updated from camera info)
3234
self.fx, self.fy, self.cx, self.cy = 525.0, 525.0, 320.0, 240.0
33-
34-
self.voxel_size = 0.04
35-
self.max_range = 3.5
36-
35+
36+
self.voxel_size = 0.04
37+
self.max_range = 3.5
38+
3739
self.get_logger().info('OctoMap Node started - subscribing to processed perception data')
3840

3941
def info_callback(self, msg):
@@ -42,7 +44,8 @@ def info_callback(self, msg):
4244
self.fy = msg.k[4]
4345
self.cx = msg.k[2]
4446
self.cy = msg.k[5]
45-
self.get_logger().info(f'Updated camera intrinsics: fx={self.fx}, fy={self.fy}')
47+
self.get_logger().info(
48+
f'Updated camera intrinsics: fx={self.fx}, fy={self.fy}')
4649

4750
def rgb_callback(self, msg):
4851
"""Receive processed RGB image from perception node."""
@@ -58,11 +61,11 @@ def depth_callback(self, msg):
5861

5962
# TODO: Implement point cloud generation and octomap updating
6063

61-
64+
6265
def main(args=None):
6366
rclpy.init(args=args)
6467
node = OctoMapNode()
65-
68+
6669
try:
6770
rclpy.spin(node)
6871
except KeyboardInterrupt:
@@ -71,5 +74,6 @@ def main(args=None):
7174
node.destroy_node()
7275
rclpy.shutdown()
7376

77+
7478
if __name__ == '__main__':
75-
main()
79+
main()

autonomy/behaviour/octo_map/setup.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,8 @@
1010
packages=[package_name],
1111
data_files=[
1212
# Install marker file in the package index
13-
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
13+
('share/ament_index/resource_index/packages',
14+
['resource/' + package_name]),
1415
# Include our package.xml file
1516
(os.path.join('share', package_name), ['package.xml']),
1617
# Include all launch files.
@@ -32,4 +33,4 @@
3233
'octo_map_node = octo_map.octo_map_node:main'
3334
],
3435
},
35-
)
36+
)

autonomy/behaviour/voxel_grid/launch/voxel_grid.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,4 +10,4 @@ def generate_launch_description():
1010
executable='voxel_grid_node',
1111
output='screen',
1212
emulate_tty=True),
13-
])
13+
])

autonomy/behaviour/voxel_grid/setup.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,8 @@
1010
packages=[package_name],
1111
data_files=[
1212
# Install marker file in the package index
13-
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
13+
('share/ament_index/resource_index/packages',
14+
['resource/' + package_name]),
1415
# Include our package.xml file
1516
(os.path.join('share', package_name), ['package.xml']),
1617
# Include all launch files.
@@ -32,4 +33,4 @@
3233
'voxel_grid_node = voxel_grid.voxel_grid_node:main'
3334
],
3435
},
35-
)
36+
)

autonomy/behaviour/voxel_grid/voxel_grid/voxel_grid_node.py

Lines changed: 45 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -23,14 +23,20 @@ def __init__(self):
2323
super().__init__('voxel_grid_node')
2424

2525
self.rgb_sub = self.create_subscription(
26-
Image, '/camera/color/image_raw', self.rgb_callback, qos_profile_sensor_data
27-
)
26+
Image,
27+
'/camera/color/image_raw',
28+
self.rgb_callback,
29+
qos_profile_sensor_data)
2830
self.depth_sub = self.create_subscription(
29-
Image, '/camera/depth/image_raw', self.depth_callback, qos_profile_sensor_data
30-
)
31+
Image,
32+
'/camera/depth/image_raw',
33+
self.depth_callback,
34+
qos_profile_sensor_data)
3135
self.info_sub = self.create_subscription(
32-
CameraInfo, '/camera/depth/camera_info', self.info_callback, qos_profile_sensor_data
33-
)
36+
CameraInfo,
37+
'/camera/depth/camera_info',
38+
self.info_callback,
39+
qos_profile_sensor_data)
3440

3541
self.voxel_pub = self.create_publisher(
3642
PointCloud2, '/behaviour/voxel_grid', qos_profile_sensor_data
@@ -42,10 +48,10 @@ def __init__(self):
4248
self.fx, self.fy, self.cx, self.cy = 525.0, 525.0, 320.0, 240.0
4349
self.have_intrinsics = False
4450

45-
self.voxel_size = 0.04
46-
self.max_range = 3.5
47-
self.min_range = 0.1
48-
self.stride = 4
51+
self.voxel_size = 0.04
52+
self.max_range = 3.5
53+
self.min_range = 0.1
54+
self.stride = 4
4955

5056
self.get_logger().info('Voxel Grid Node started (world modelling, headless)')
5157

@@ -67,18 +73,34 @@ def _decode_depth(msg: Image) -> np.ndarray:
6773
enc = (msg.encoding or '').lower()
6874

6975
if enc in ('mono16', '16uc1'):
70-
d = np.frombuffer(msg.data, dtype=np.uint16).reshape(msg.height, msg.width)
76+
d = np.frombuffer(
77+
msg.data,
78+
dtype=np.uint16).reshape(
79+
msg.height,
80+
msg.width)
7181
return (d.astype(np.float32) / 1000.0) # mm -> m
7282

7383
if enc == '32fc1':
74-
d = np.frombuffer(msg.data, dtype=np.float32).reshape(msg.height, msg.width)
84+
d = np.frombuffer(
85+
msg.data,
86+
dtype=np.float32).reshape(
87+
msg.height,
88+
msg.width)
7589
return d
7690

7791
if enc == '16fc1':
78-
d = np.frombuffer(msg.data, dtype=np.float16).reshape(msg.height, msg.width)
92+
d = np.frombuffer(
93+
msg.data,
94+
dtype=np.float16).reshape(
95+
msg.height,
96+
msg.width)
7997
return d.astype(np.float32)
8098

81-
d = np.frombuffer(msg.data, dtype=np.uint16).reshape(msg.height, msg.width)
99+
d = np.frombuffer(
100+
msg.data,
101+
dtype=np.uint16).reshape(
102+
msg.height,
103+
msg.width)
82104
return (d.astype(np.float32) / 1000.0)
83105

84106
# ---------- callbacks ----------
@@ -89,7 +111,8 @@ def info_callback(self, msg: CameraInfo):
89111
self.cy = float(msg.k[5])
90112
self.have_intrinsics = True
91113

92-
self.get_logger().info(f'Intrinsics updated: fx={self.fx:.2f}, fy={self.fy:.2f}, cx={self.cx:.2f}, cy={self.cy:.2f}')
114+
self.get_logger().info(
115+
f'Intrinsics updated: fx={self.fx:.2f}, fy={self.fy:.2f}, cx={self.cx:.2f}, cy={self.cy:.2f}')
93116

94117
def rgb_callback(self, msg: Image):
95118
self.rgb_image = self._decode_rgb_bgr8(msg)
@@ -117,7 +140,7 @@ def process_rgbd_if_ready(self):
117140

118141
self.publish_voxel_grid(voxel_centers)
119142

120-
#reset
143+
# reset
121144
self.depth_image = None
122145
self.rgb_image = None
123146

@@ -165,14 +188,15 @@ def create_voxel_grid(self, points: np.ndarray) -> np.ndarray:
165188

166189
voxel_gen = PointToVoxel(
167190
vsize_xyz=[self.voxel_size, self.voxel_size, self.voxel_size],
168-
coors_range_xyz=coors_range_m.tolist(), #Convert numpy to python
191+
coors_range_xyz=coors_range_m.tolist(), # Convert numpy to python
169192
num_point_features=3,
170193
max_num_voxels=10000,
171194
max_num_points_per_voxel=20
172195
)
173196

174197
pc_tensor = torch.from_numpy(points) # float32
175-
voxels, indices, num_points = voxel_gen(pc_tensor) # indices: [M, 3] (z,y,x) or (x,y,z) depending on impl
198+
# indices: [M, 3] (z,y,x) or (x,y,z) depending on impl
199+
voxels, indices, num_points = voxel_gen(pc_tensor)
176200

177201
if indices.numel() == 0:
178202
return np.zeros((0, 3), dtype=np.float32)
@@ -186,13 +210,14 @@ def create_voxel_grid(self, points: np.ndarray) -> np.ndarray:
186210
origin = coors_range_m[:3] # meters
187211
centers = origin + (idx_xyz + 0.5) * self.voxel_size # meters
188212

189-
self.get_logger().info(f'Voxels: {centers.shape[0]} from points: {points.shape[0]}')
213+
self.get_logger().info(
214+
f'Voxels: {centers.shape[0]} from points: {points.shape[0]}')
190215
return centers.astype(np.float32)
191216

192217
def publish_voxel_grid(self, voxel_centers: np.ndarray):
193218
header = Header()
194219
header.stamp = self.get_clock().now().to_msg()
195-
header.frame_id = 'camera_link'
220+
header.frame_id = 'camera_link'
196221

197222
fields = [
198223
PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1),

autonomy/perception/launch/perception.launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ def generate_launch_description():
1111
default_value='info',
1212
description='Log level for the dummy publisher node'
1313
),
14-
14+
1515
Node(
1616
package='perception',
1717
executable='dummy_publisher_node',
@@ -24,4 +24,4 @@ def generate_launch_description():
2424
# Add any topic remappings here if needed
2525
]
2626
)
27-
])
27+
])

autonomy/perception/perception/dummy_publisher_node.py

Lines changed: 32 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -46,27 +46,49 @@ def publish_dummy_data(self):
4646

4747
# Create a simple scene with geometric shapes at different depths
4848
rgb_image = np.zeros((480, 640, 3), dtype=np.uint8)
49-
depth_image = np.full((480, 640), 3000, dtype=np.uint16) # Background at 3000mm
49+
depth_image = np.full(
50+
(480, 640), 3000, dtype=np.uint16) # Background at 3000mm
5051

5152
# Add a large rectangle (closer object) - like a wall or box
52-
cv2.rectangle(rgb_image, (150, 120), (490, 360), (100, 150, 200), -1) # Filled rectangle
53-
cv2.rectangle(depth_image, (150, 120), (490, 360), 1200, -1) # 1200mm depth
53+
cv2.rectangle(rgb_image, (150, 120), (490, 360),
54+
(100, 150, 200), -1) # Filled rectangle
55+
cv2.rectangle(depth_image, (150, 120), (490, 360),
56+
1200, -1) # 1200mm depth
5457

5558
# Add a smaller circle (closest object) - like a ball
56-
cv2.circle(rgb_image, (320, 240), 80, (50, 200, 50), -1) # Green circle
57-
cv2.circle(depth_image, (320, 240), 80, 800, -1) # 800mm depth (closest)
59+
cv2.circle(rgb_image, (320, 240), 80,
60+
(50, 200, 50), -1) # Green circle
61+
# 800mm depth (closest)
62+
cv2.circle(depth_image, (320, 240), 80, 800, -1)
5863

5964
# Add another rectangle (medium distance)
60-
cv2.rectangle(rgb_image, (50, 300), (200, 450), (200, 100, 100), -1) # Reddish rectangle
61-
cv2.rectangle(depth_image, (50, 300), (200, 450), 1800, -1) # 1800mm depth
65+
cv2.rectangle(rgb_image, (50, 300), (200, 450),
66+
(200, 100, 100), -1) # Reddish rectangle
67+
cv2.rectangle(depth_image, (50, 300), (200, 450),
68+
1800, -1) # 1800mm depth
6269

6370
# Optional: Add some gradient/texture to make it more realistic
6471
noise = np.random.randint(-20, 20, rgb_image.shape, dtype=np.int16)
65-
rgb_image = np.clip(rgb_image.astype(np.int16) + noise, 0, 255).astype(np.uint8)
72+
rgb_image = np.clip(
73+
rgb_image.astype(
74+
np.int16) +
75+
noise,
76+
0,
77+
255).astype(
78+
np.uint8)
6679

6780
# Add slight depth variation (noise)
68-
depth_noise = np.random.randint(-30, 30, depth_image.shape, dtype=np.int16)
69-
depth_image = np.clip(depth_image.astype(np.int32) + depth_noise, 0, 65535).astype(np.uint16)
81+
depth_noise = np.random.randint(-30,
82+
30,
83+
depth_image.shape,
84+
dtype=np.int16)
85+
depth_image = np.clip(
86+
depth_image.astype(
87+
np.int32) +
88+
depth_noise,
89+
0,
90+
65535).astype(
91+
np.uint16)
7092

7193
rgb_msg = self.bridge.cv2_to_imgmsg(
7294
rgb_image, encoding='bgr8'

autonomy/perception/setup.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,8 @@
1010
packages=[package_name],
1111
data_files=[
1212
# Install marker file in the package index
13-
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
13+
('share/ament_index/resource_index/packages',
14+
['resource/' + package_name]),
1415
# Include our package.xml file
1516
(os.path.join('share', package_name), ['package.xml']),
1617
# Include all launch files.
@@ -32,4 +33,4 @@
3233
'dummy_publisher_node = perception.dummy_publisher_node:main'
3334
],
3435
},
35-
)
36+
)

0 commit comments

Comments
 (0)