@@ -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 ),
0 commit comments