Skip to content

Commit f4d7e2d

Browse files
committed
Related start frame agents to vehicle frame agents. Fixed time
1 parent 23abe25 commit f4d7e2d

1 file changed

Lines changed: 38 additions & 12 deletions

File tree

GEMstack/onboard/perception/pedestrian_detection.py

Lines changed: 38 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333
import os
3434
from typing import List, Dict
3535
from collections import defaultdict
36-
from datetime import datetime
36+
# from datetime import datetime
3737
from copy import deepcopy
3838
# ROS, CV
3939
import rospy
@@ -121,7 +121,7 @@ def __init__(self, vehicle_interface : GEMInterface) -> None:
121121
self.id_tracker = IdTracker()
122122

123123
# Update function variables
124-
self.t_start = datetime.now() # Estimated start frame time
124+
self.t_start = None # Estimated start frame time
125125
self.start_pose_abs = None # Get this from GNSS (GLOBAL frame)
126126
self.current_vehicle_state = None # Current vehicle state from GNSS in GLOBAL frame
127127
self.previous_vehicle_state = None # Previous vehicle state from GNSS in GLOBAL frame
@@ -143,6 +143,8 @@ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
143143
# Storing initial pose
144144
if (self.start_pose_abs == None):
145145
self.start_pose_abs = vehicle.pose
146+
if self.t_start == None:
147+
self.t_start = vehicle.pose.t
146148
return self.current_agents
147149
else:
148150
self.previous_vehicle_state = self.current_vehicle_state
@@ -151,6 +153,8 @@ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
151153
if(self.current_agent_obj_dims == {}):
152154
return self.current_agents
153155

156+
# Update current time:
157+
self.curr_time = vehicle.pose.t
154158

155159
# (f"Global state : {vehicle}")
156160

@@ -175,11 +179,26 @@ def update(self, vehicle : VehicleState) -> Dict[str,AgentState]:
175179
agents = self.create_agent_states(obj_centers=self.current_agent_obj_dims['pose'], obj_dims=self.current_agent_obj_dims['dims'])
176180

177181
# Calculating the velocity of agents and tracking their ids
178-
self.find_vels_and_ids(agents=agents)
182+
backOrder = self.find_vels_and_ids(agents=agents)
179183

180-
# Convert to current vehicle frame from starting frame here for planning group.
184+
# Create a dictionary of vehicle frame agents:
185+
vehicle_agents = self.create_vehicle_dict(agents, backOrder)
186+
# Create a list containing the ids of the new agents in the vehicle frame agent's order
181187

182-
return self.current_agents
188+
print("VEHICLE AGENTS")
189+
print(vehicle_agents)
190+
191+
return vehicle_agents
192+
193+
def create_vehicle_dict(self, agents: List[AgentState], backOrder: List[int]):
194+
vehicle_agents = {}
195+
196+
for idx in backOrder:
197+
vehicle_agents[backOrder[idx]] = agents[idx]
198+
vehicle_agents[backOrder[idx]].activity = self.current_agents[backOrder[idx]].activity
199+
vehicle_agents[backOrder[idx]].velocity = self.current_agents[backOrder[idx]].velocity
200+
201+
return vehicle_agents
183202

184203
# TODO: Improve Algo Knn, ransac, etc.
185204
def find_centers(self, clusters: List[List[np.ndarray]]) -> List[np.ndarray]:
@@ -302,6 +321,7 @@ def update_object_states(self, track_result: List[Results], extracted_pts_all: L
302321
obj_dims = self.find_dims(pedestrians_3d_pts) # 8 point dims of bounding box
303322
# Pose is stored in vehicle frame and converted to start frame in the update function
304323
obj_centers_vehicle = []
324+
obj_dims_vehicle = []
305325
if self.vehicle_frame:
306326
for obj_center in obj_centers:
307327
if obj_center.size > 0:
@@ -313,7 +333,6 @@ def update_object_states(self, track_result: List[Results], extracted_pts_all: L
313333
obj_centers = obj_centers_vehicle
314334

315335
if(len(obj_center) != 0) and (len(obj_dims) != 0):
316-
obj_dims_vehicle = []
317336
for obj_dim in obj_dims:
318337
if len(obj_dim) > 0:
319338
# obj_dim_min = np.array([obj_dim[0]])
@@ -336,6 +355,11 @@ def update_object_states(self, track_result: List[Results], extracted_pts_all: L
336355
def find_vels_and_ids(self, agents: List[AgentState]):
337356
# self.prev_agents was assigned a deepcopy of self.current_agents and then self.current_agents
338357
# was cleared before this function was called
358+
359+
# Create a list containing the ids of the new agents in the vehicle frame agent's order
360+
backOrder = []
361+
for each in agents:
362+
backOrder.append(None)
339363

340364
# Nothing was scanned, erase current (for current output) and previous list (for next time through because nothing was scanned)
341365
if (len(agents) == 0):
@@ -359,7 +383,7 @@ def find_vels_and_ids(self, agents: List[AgentState]):
359383
vel = [0, 0, 0]
360384
else:
361385
delta_t = self.curr_time - self.prev_time
362-
vel = list((np.array([agents[idx].pose.x, agents[idx].pose.y, agents[idx].pose.z]) - np.array([prev_state.pose.x, prev_state.pose.y, prev_state.pose.z])) / delta_t.total_seconds())
386+
vel = list((np.array([agents[idx].pose.x, agents[idx].pose.y, agents[idx].pose.z]) - np.array([prev_state.pose.x, prev_state.pose.y, prev_state.pose.z])) / delta_t)
363387
# print("VELOCITY:")
364388
# print(vel)
365389

@@ -369,6 +393,7 @@ def find_vels_and_ids(self, agents: List[AgentState]):
369393
agents[idx].velocity = (0, 0, 0) if len(vel) == 0 else tuple(vel)
370394

371395
self.current_agents[prev_id] = agents[idx]
396+
backOrder[idx] = prev_id
372397
del self.prev_agents[prev_id] # Remove previous agent from previous agents so it doesn't get assigned multiple times on accident
373398
break
374399

@@ -380,6 +405,8 @@ def find_vels_and_ids(self, agents: List[AgentState]):
380405
agents[idx].activity = AgentActivityEnum.UNDETERMINED
381406
agents[idx].velocity = (0, 0, 0)
382407
self.current_agents[id] = agents[idx]
408+
backOrder[idx] = id
409+
return backOrder
383410

384411
# Calculates whether 2 agents overlap. True if they do, false if not
385412
def agents_overlap(self, curr_agent: AgentState, prev_agent: AgentState) -> bool:
@@ -426,7 +453,7 @@ def create_agent_states(self, obj_centers: List[np.ndarray], obj_dims: List[np.n
426453
for idx in range(num_pairings):
427454
# Create agent in current frame:
428455
agents.append(AgentState(
429-
pose=ObjectPose(t=(self.curr_time - self.t_start).total_seconds(), x=obj_centers[idx][0], y=obj_centers[idx][1], z=obj_centers[idx][2] - xyz_lengths_start[idx][2]/2.0, yaw=0,pitch=0,roll=0,frame=ObjectFrameEnum.CURRENT),
456+
pose=ObjectPose(t=self.curr_time - self.t_start, x=obj_centers[idx][0], y=obj_centers[idx][1], z=obj_centers[idx][2] - xyz_lengths_start[idx][2]/2.0, yaw=0,pitch=0,roll=0,frame=ObjectFrameEnum.CURRENT),
430457
# Beware: AgentState(PhysicalObject) builds bbox from
431458
# dims [-l/2,l/2] x [-w/2,w/2] x [0,h], not
432459
# [-l/2,l/2] x [-w/2,w/2] x [-h/2,h/2]
@@ -435,10 +462,9 @@ def create_agent_states(self, obj_centers: List[np.ndarray], obj_dims: List[np.n
435462
dimensions=(xyz_lengths_start[idx][0], xyz_lengths_start[idx][1], xyz_lengths_start[idx][2]),
436463
outline=None,
437464
type=AgentEnum.PEDESTRIAN,
438-
activity=AgentActivityEnum.UNDETERMINED, # TODO
439-
velocity=None, # TODO
465+
activity=AgentActivityEnum.UNDETERMINED, # Temporary
466+
velocity=None, # Temporary
440467
yaw_rate=0,
441-
track_id = None # TODO
442468
))
443469

444470
return agents
@@ -502,7 +528,7 @@ def ouster_oak_callback(self, cv_image: cv2.Mat, lidar_points: np.ndarray):
502528

503529
# Update times for basic velocity calculation
504530
self.prev_time = self.curr_time
505-
self.curr_time = datetime.now()
531+
# self.curr_time = datetime.now() # Updating in update function now
506532

507533
self.cv_image = cv_image
508534
self.lidar_points = lidar_points

0 commit comments

Comments
 (0)