Skip to content

Commit 32f0025

Browse files
Merge pull request #132 from krishauser/perceptionb_start_frame
pedestrian_detection.py Convert obj_dims to start frame aligned bbox
2 parents e0cd0a8 + d3f6190 commit 32f0025

1 file changed

Lines changed: 35 additions & 16 deletions

File tree

GEMstack/onboard/perception/pedestrian_detection.py

Lines changed: 35 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -167,14 +167,11 @@ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
167167
if(self.current_agent_obj_dims == {}):
168168
return self.current_agents
169169

170-
print(f"Global state : {vehicle}")
170+
171+
(f"Global state : {vehicle}")
171172

172173
# Convert pose to start state. Need to use previous_vehicle state as pedestrian info is delayed
173174
vehicle_start_pose = vehicle.pose.to_frame(ObjectFrameEnum.START,self.previous_vehicle_state.pose,self.start_pose_abs)
174-
print(f"Start state : {vehicle_start_pose}")
175-
176-
print(f"ped pose vehicle state = {self.current_agent_obj_dims['pose']}")
177-
print(f"ped dimenstions vehicle state = {self.current_agent_obj_dims['dims']}")
178175

179176
# converting to start frame
180177
for i,pose in enumerate(self.current_agent_obj_dims['pose']):
@@ -183,10 +180,6 @@ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
183180
for i,dims in enumerate(self.current_agent_obj_dims['dims']):
184181
self.current_agent_obj_dims['dims'][i] = np.array(vehicle_start_pose.apply(dims))
185182

186-
187-
print(f"ped pose start state = {self.current_agent_obj_dims['pose']}")
188-
print(f"ped dimenstions start state = {self.current_agent_obj_dims['dims']}")
189-
190183
# Prepare variables for find_vels_and_ids
191184
self.prev_agents = self.current_agents.copy()
192185
self.current_agents.clear()
@@ -219,9 +212,18 @@ def find_dims(self, clusters: List[List[np.ndarray]]) -> List[np.ndarray]:
219212
# objects distance to ground we filtered from lidar,
220213
# other heuristics to imrpove stability for find_ funcs ?
221214
clusters = [np.array(clust) for clust in clusters]
215+
# x, y, z 1 value
222216
dims = [np.array(()) if clust.size == 0 else np.max(clust, axis= 0) - np.min(clust, axis= 0) for clust in clusters]
217+
# x, y, z convert to 2 values around origin
218+
for i in range(len(dims)):
219+
if dims[i].size() == 0: continue
220+
else:
221+
dims[i] = np.vstack(0-dims[i]/2, dims[i]/2)
222+
223+
# Dims are 2 points: [ [min_x, min_y, min_z], [max_x, max_y, max_z] ]
224+
# Need that for transform
223225
return dims
224-
226+
225227
# TODO: Separate debug/viz class, bbox and 2d 3d points funcs
226228
def viz_object_states(self, cv_image, boxes, extracted_pts_all):
227229
# Extract 3D pedestrians points in lidar frame
@@ -305,6 +307,7 @@ def update_object_states(self, track_result: List[Results], extracted_pts_all: L
305307
# TODO: Combine funcs for efficiency in C.
306308
# Separate numpy prob still faster for now
307309
obj_centers = self.find_centers(pedestrians_3d_pts) # Centers are calculated in lidar frame here
310+
# Dims are 2 points: [ [min_x, min_y, min_z], [max_x, max_y, max_z] ]
308311
obj_dims = self.find_dims(pedestrians_3d_pts)
309312
# Pose is stored in vehicle frame and converted to start frame in the update function
310313
obj_centers_vehicle = []
@@ -318,8 +321,19 @@ def update_object_states(self, track_result: List[Results], extracted_pts_all: L
318321
obj_centers = obj_centers_vehicle
319322

320323
if(len(obj_center) != 0) and (len(obj_dims) != 0):
321-
self.current_agent_obj_dims["pose"] = obj_center
322-
self.current_agent_obj_dims["dims"] = obj_dims
324+
obj_dims_vehicle = []
325+
for obj_dim in obj_dims:
326+
if len(obj_dim) > 0:
327+
obj_dim_min = np.array([obj_dim[0]])
328+
obj_dim_max = np.array([obj_dim[1]])
329+
obj_dim_min_vehicle = transform_lidar_points(obj_dim_min, self.R_lidar_to_vehicle, self.t_lidar_to_vehicle)[0]
330+
obj_dim_max_vehicle = transform_lidar_points(obj_dim_max, self.R_lidar_to_vehicle, self.t_lidar_to_vehicle)[0]
331+
else: obj_dims_vehicle.append(np.array(()))
332+
obj_dims = obj_dims_vehicle
333+
334+
self.current_agent_obj_dims["pose"] = obj_centers
335+
self.current_agent_obj_dims["dims"] = obj_dims
336+
323337

324338
# TODO: Refactor to make more efficient
325339
# TODO: Moving Average across last N iterations pos/vel? Less spurious vals
@@ -392,14 +406,19 @@ def agents_overlap(self, curr_agent: AgentState, prev_agent: AgentState) -> bool
392406
)
393407

394408
def create_agent_states(self, obj_centers: List[np.ndarray], obj_dims: List[np.ndarray]) -> List[AgentState]:
409+
# Dims are 2 points: [ [min_x, min_y, min_z], [max_x, max_y, max_z] ]
410+
395411
# Gate to check whether dims and centers are empty (will happen if no pedestrians are scanned):
396412
for idx in range(len(obj_dims) -1, -1, -1):
397413
if (obj_centers[idx].size == 0) or (obj_dims[0].size == 0):
398414
del obj_centers[idx]
399415
del obj_dims[idx]
400-
elif (obj_centers[idx].size != obj_dims[0].size):
401-
del obj_centers[idx]
402-
del obj_dims[idx]
416+
417+
# Convert from 2 point to 1 point dims
418+
obj_dims = [np.abs( dim[0] - dim[1]) for dim in obj_dims]
419+
# elif (obj_centers[idx].size != obj_dims[0].size):
420+
# del obj_centers[idx]
421+
# del obj_dims[idx]
403422
# Create list of agent states in current vehicle frame:
404423
agents = []
405424
num_pairings = len(obj_centers)
@@ -413,7 +432,7 @@ def create_agent_states(self, obj_centers: List[np.ndarray], obj_dims: List[np.n
413432
# [-l/2,l/2] x [-w/2,w/2] x [-h/2,h/2]
414433
# (l, w, h)
415434
# TODO: confirm (z -> l, x -> w, y -> h)
416-
dimensions=(obj_dims[idx][0], obj_dims[idx][1], obj_centers[idx][2] + obj_dims[idx][2]),
435+
dimensions=(obj_dims[idx][2], obj_dims[idx][0], obj_centers[idx][1]), # obj_dims[idx][0], obj_dims[idx][1], obj_centers[idx][2] + obj_dims[idx][2]
417436
outline=None,
418437
type=AgentEnum.PEDESTRIAN,
419438
activity=AgentActivityEnum.UNDETERMINED, # Temporary

0 commit comments

Comments
 (0)