33from ..component import Component
44# from .perception_utils import *
55from .pedestrian_utils_gem import *
6+ from .pedestrian_utils import pose_to_matrix
67from typing import Dict
78import rospy
89from message_filters import Subscriber , ApproximateTimeSynchronizer
@@ -97,16 +98,18 @@ def __init__(
9798 vehicle_interface : GEMInterface ,
9899 enable_tracking : bool = True ,
99100 use_start_frame : bool = True ,
100- iou_threshold : float = 0.1 ,
101+ iou_threshold : float = 0.001 ,
101102 ** kwargs
102103 ):
103104 self .vehicle_interface = vehicle_interface
104105 self .tracked_agents : Dict [str , AgentState ] = {}
105- self .ped_counter = 0
106+ self .pedestrian_counter = 0
106107 self .latest_yolo_bbxs : Optional [BoundingBoxArray ] = None
107108 self .latest_pp_bbxs : Optional [BoundingBoxArray ] = None
108109 self .start_pose_abs : Optional [ObjectPose ] = None
109110 self .start_time : Optional [float ] = None
111+ self .current_agents = {}
112+ self .tracked_agents = {}
110113
111114 self .enable_tracking = enable_tracking
112115 self .use_start_frame = use_start_frame
@@ -162,16 +165,7 @@ def update(self, vehicle: VehicleState) -> Dict[str, AgentState]:
162165 self .start_pose_abs = vehicle .pose
163166 rospy .loginfo ("CombinedDetector3D latched start pose." )
164167
165- current_frame_agents = self ._fuse_bounding_boxes (yolo_bbx_array , pp_bbx_array , vehicle , current_time )
166-
167- return {}
168- # if self.enable_tracking:
169- # self._update_tracking(current_frame_agents)
170- # else:
171- # self.tracked_agents = current_frame_agents # NOTE: No deepcopy
172-
173- # return self.tracked_agents
174-
168+ return self ._fuse_bounding_boxes (yolo_bbx_array , pp_bbx_array , vehicle , current_time )
175169
176170 def _fuse_bounding_boxes (self ,
177171 yolo_bbx_array : BoundingBoxArray ,
@@ -180,7 +174,7 @@ def _fuse_bounding_boxes(self,
180174 current_time : float
181175 ) -> Dict [str , AgentState ]:
182176 original_header = yolo_bbx_array .header
183- current_agents_in_frame : Dict [str , AgentState ] = {}
177+ agents : Dict [str , AgentState ] = {}
184178 yolo_boxes : List [BoundingBox ] = yolo_bbx_array .boxes
185179 pp_boxes : List [BoundingBox ] = pp_bbx_array .boxes
186180
@@ -239,63 +233,85 @@ def _fuse_bounding_boxes(self,
239233 quat_x = box .pose .orientation .x ; quat_y = box .pose .orientation .y ; quat_z = box .pose .orientation .z ; quat_w = box .pose .orientation .w
240234 yaw , pitch , roll = R .from_quat ([quat_x , quat_y , quat_z , quat_w ]).as_euler ('zyx' , degrees = False )
241235
242- # Start frame
243- if self .use_start_frame and self .start_pose_abs is not None :
244- vehicle_pose_in_start_frame = vehicle_state .pose .to_frame (
245- ObjectFrameEnum .START , vehicle_state .pose , self .start_pose_abs
246- )
247- T_vehicle_to_start = pose_to_matrix (vehicle_pose_in_start_frame )
248- object_pose_current_h = np .array ([[pos_x ],[pos_y ],[pos_z ],[1.0 ]])
249- object_pose_start_h = T_vehicle_to_start @ object_pose_current_h
250- final_x , final_y , final_z = object_pose_start_h [:3 , 0 ]
251- else :
252- final_x , final_y , final_z = pos_x , pos_y , pos_z
236+ # Convert to start frame
237+ vehicle_pose_in_start_frame = vehicle_state .pose .to_frame (
238+ ObjectFrameEnum .START , vehicle_state .pose , self .start_pose_abs
239+ )
240+ T_vehicle_to_start = pose_to_matrix (vehicle_pose_in_start_frame )
241+ object_pose_current_h = np .array ([[pos_x ],[pos_y ],[pos_z ],[1.0 ]])
242+ object_pose_start_h = T_vehicle_to_start @ object_pose_current_h
243+ final_x , final_y , final_z = object_pose_start_h [:3 , 0 ]
253244
254- final_pose = ObjectPose (
245+ new_pose = ObjectPose (
255246 t = current_time , x = final_x , y = final_y , z = final_z ,
256247 yaw = yaw , pitch = pitch , roll = roll , frame = output_frame_enum
257248 )
258249 dims = (box .dimensions .x , box .dimensions .y , box .dimensions .z )
259- ######### Mapping based on label (integer) from BoundingBox msg
260- agent_type = AgentEnum . PEDESTRIAN if box . label == 0 else AgentEnum . UNKNOWN # Needs refinement
261- activity = AgentActivityEnum . UNKNOWN # Placeholder
262-
263- # temp id
264- # _update_tracking assign persistent IDs
265- temp_agent_id = f"pedestrian { i } "
266-
267- current_agents_in_frame [ temp_agent_id ] = AgentState (
268- pose = final_pose , dimensions = dims , outline = None , type = agent_type ,
269- activity = activity , velocity = ( 0.0 , 0.0 , 0.0 ), yaw_rate = 0.0
270- # score=box.value # score
250+
251+ new_pose = ObjectPose (
252+ t = current_time , x = final_x , y = final_y , z = final_z - box . dimensions . z / 2.0 ,
253+ yaw = yaw , pitch = pitch , roll = roll , frame = output_frame_enum
254+ )
255+ dims [ 2 ] = dims [ 2 ] * 2.0 # AgentState has z center on the floor and height is full height.
256+
257+ existing_id = match_existing_pedestrian (
258+ new_center = np . array ([ new_pose . x , new_pose . y , new_pose . z ]),
259+ new_dims = dims ,
260+ existing_agents = self . tracked_agents ,
261+ distance_threshold = 2.0
271262 )
263+
264+ if existing_id is not None :
265+ old_state = self .tracked_agents [existing_id ]
266+ dt = new_pose .t - old_state .pose .t
267+ vx , vy , vz = compute_velocity (old_state .pose , new_pose , dt )
268+ updated_agent = AgentState (
269+ pose = new_pose ,
270+ dimensions = dims ,
271+ outline = None ,
272+ type = AgentEnum .PEDESTRIAN ,
273+ activity = AgentActivityEnum .MOVING ,
274+ velocity = (vx , vy , vz ),
275+ yaw_rate = 0
276+ )
277+ agents [existing_id ] = updated_agent
278+ self .tracked_agents [existing_id ] = updated_agent
279+ else :
280+ agent_id = f"pedestrian{ self .pedestrian_counter } "
281+ self .pedestrian_counter += 1
282+ new_agent = AgentState (
283+ pose = new_pose ,
284+ dimensions = dims ,
285+ outline = None ,
286+ type = AgentEnum .PEDESTRIAN ,
287+ activity = AgentActivityEnum .MOVING ,
288+ velocity = (0 , 0 , 0 ),
289+ yaw_rate = 0
290+ )
291+ agents [agent_id ] = new_agent
292+ self .tracked_agents [agent_id ] = new_agent
293+
272294 except Exception as e :
273295 rospy .logwarn (f"Failed to convert final BoundingBox { i } to AgentState: { e } " )
274296 continue
275297
276298 self .pub_fused .publish (fused_bb_array )
277- return current_agents_in_frame
278-
279-
280- def _update_tracking (self , current_frame_agents : Dict [str , AgentState ]):
281-
282- # Todo tracking
283- ## Match 'current_frame_agents' to 'self.tracked_agents'.
284- ## - Use position (already in correct START or CURRENT frame), maybe size/type.
285- ## - Need a matching algorithm (e.g., nearest neighbor within radius, Hungarian).
286- ## For matched pairs:
287- ## - Update the existing agent in 'self.tracked_agents' (e.g., smooth pose, update timestamp).
288- ## For unmatched 'current_frame_agents':
289- ## - These are new detections. Assign a persistent ID (e.g., f"Ped_{self.ped_counter}").
290- ## - Increment self.ped_counter.
291- ## - Add them to 'self.tracked_agents'.
292- ## For unmatched 'self.tracked_agents' (agents not seen this frame):
293- ## - Increment a 'missed frames' counter or check timestamp.
294- ## - If missed for too long (e.g., > 1 second), remove from 'self.tracked_agents'.
295-
296- # return without tracking
297- self .tracked_agents = current_frame_agents
298299
300+ stale_ids = [agent_id for agent_id , agent in self .tracked_agents .items ()
301+ if current_time - agent .pose .t > 5.0 ]
302+ for agent_id in stale_ids :
303+ rospy .loginfo (f"Removing stale agent: { agent_id } \n " )
304+ for agent_id , agent in agents .items ():
305+ p = agent .pose
306+ # Format pose and velocity with 3 decimals (or as needed)
307+ rospy .loginfo (
308+ f"Agent ID: { agent_id } \n "
309+ f"Pose: (x: { p .x :.3f} , y: { p .y :.3f} , z: { p .z :.3f} , "
310+ f"yaw: { p .yaw :.3f} , pitch: { p .pitch :.3f} , roll: { p .roll :.3f} )\n "
311+ f"Velocity: (vx: { agent .velocity [0 ]:.3f} , vy: { agent .velocity [1 ]:.3f} , vz: { agent .velocity [2 ]:.3f} )\n "
312+ )
313+
314+ return agents
299315
300316
301317# Fake 2D Combined Detector for testing purposes
0 commit comments