1+ import sys
2+ import os
3+ sys .path .append (os .getcwd ())
4+
5+ from GEMstack .state import AgentEnum
6+ import json
7+ import matplotlib .pyplot as plt
8+ import numpy as np
9+
10+ CMAP = "RdYlGn"
11+
12+ def compute_safety_factor (value , safe_thresh , unsafe_thresh , flip = False ):
13+ """
14+ Computes a safety factor between 0(unsafe) and 1(safe)
15+ If flip is True, the threshold bounds are reversed.
16+ """
17+ abs_val = abs (value )
18+ if abs_val <= safe_thresh :
19+ factor = 1.0
20+ elif abs_val >= unsafe_thresh :
21+ factor = 0.0
22+ else :
23+ factor = 1.0 - (abs_val - safe_thresh ) / (unsafe_thresh - safe_thresh )
24+
25+ if flip :
26+ return 1.0 - factor
27+ return factor
28+
29+ def parse_behavior_log (filename ):
30+ """
31+ Parses the behavior log file and extracts the following data:
32+ - vehicle time
33+ - vehicle acceleration
34+ - vehicle heading rate
35+ - pedestrian time
36+ - pedestrian distance
37+ """
38+ times = []
39+ accelerations = []
40+ heading_rates = []
41+ pedestrian_times = []
42+ pedestrian_distances = []
43+
44+ with open (filename , 'r' ) as f :
45+ for line in f :
46+ try :
47+ entry = json .loads (line )
48+ except json .JSONDecodeError :
49+ print (f"Skipping invalid JSON line: { line .strip ()} " )
50+ continue
51+ # Process vehicle state data
52+ if "vehicle" in entry :
53+ t = entry .get ("time" )
54+ vehicle_data = entry ["vehicle" ].get ("data" , {})
55+ acceleration = vehicle_data .get ("acceleration" )
56+ heading_rate = vehicle_data .get ("heading_rate" )
57+ # Only add if all fields are available
58+ if None not in (t , acceleration , heading_rate ):
59+ times .append (t )
60+ accelerations .append (acceleration )
61+ heading_rates .append (heading_rate )
62+ # Process agent state data
63+ if "agents" in entry :
64+ for agent in entry ["agents" ].values ():
65+ agent_data = agent .get ("data" , {})
66+ # Check if the agent is a pedestrian
67+ if agent_data .get ("type" ) == AgentEnum .PEDESTRIAN .value :
68+ t = entry .get ("time" )
69+ pose = agent_data .get ("pose" , {})
70+ x_agent = pose .get ("x" )
71+ y_agent = pose .get ("y" )
72+ if None not in (t , x_agent , y_agent ):
73+ pedestrian_times .append (t )
74+ dist = np .sqrt (x_agent ** 2 + y_agent ** 2 )
75+ pedestrian_distances .append (dist )
76+
77+ return (np .array (times ), np .array (accelerations ), np .array (heading_rates ),
78+ np .array (pedestrian_times ), np .array (pedestrian_distances ))
79+
80+ def parse_tracker_csv (filename ):
81+ """
82+ Parses the pure pursuit tracker log file and extracts the following data:
83+ - vehicle time (from column index 18)
84+ - Crosstrack error (from column index 20)
85+ - X position actual (from column index 2)
86+ - Y position actual (from column index 5)
87+ - X position desired (from column index 11)
88+ - Y position desired (from column index 14)
89+ """
90+ data = np .genfromtxt (filename , delimiter = ',' , skip_header = 1 )
91+ vehicle_time = data [:, 18 ]
92+ cte = data [:, 20 ]
93+ x_actual , y_actual = data [:, 2 ], data [:, 5 ]
94+ x_desired , y_desired = data [:, 11 ], data [:, 14 ]
95+ return vehicle_time , cte , x_actual , y_actual , x_desired , y_desired
96+
97+ def compute_derivative (times , values ):
98+ """
99+ Computes the derivative of array with respect to time.
100+ Returns the time array and derivative values.
101+ """
102+ dt = np .diff (times )
103+ dv = np .diff (values )
104+ derivative = dv / dt
105+ return times [1 :], derivative
106+
107+ def add_safety_colorbar (figure ):
108+ """Adds a colorbar to the right of the figure"""
109+ cbar_ax = figure .add_axes ([0.92 , 0.2 , 0.02 , 0.6 ])
110+ sm = plt .cm .ScalarMappable (cmap = CMAP )
111+ cbar = figure .colorbar (sm , cax = cbar_ax )
112+ cbar .set_label ("Comfort/Safety Level" )
113+
114+ def plot_metrics (time_jerk , jerk , time_heading_acc , heading_acc , vehicle_time , cte ,
115+ x_actual , y_actual , x_desired , y_desired , pedestrian_times , pedestrian_distances ):
116+ """Plots all metrics in 2x3 grid"""
117+ fig , axs = plt .subplots (2 , 3 , figsize = (12 , 8 ))
118+ fig .subplots_adjust (hspace = 0.375 , wspace = 0.35 )
119+ axs [1 ,2 ].axis ('off' )
120+
121+ plot_jerk (axs [0 ,0 ], time_jerk , jerk )
122+ plot_heading_acceleration (axs [0 ,1 ], time_heading_acc , heading_acc )
123+ plot_crosstrack_error (axs [1 ,0 ], vehicle_time , cte )
124+ plot_position (axs [1 ,1 ], x_actual , y_actual , x_desired , y_desired )
125+ plot_pedestrian_dist (axs [0 ,2 ], pedestrian_times , pedestrian_distances )
126+
127+ # Colorbar on the right side
128+ add_safety_colorbar (fig )
129+
130+ plt .show ()
131+
132+ def plot_jerk (axis , time , jerk , safe_thresh = 1.0 , unsafe_thresh = 2.5 ):
133+ """Plots vehicle jerk (rate of acceleration) vs. time"""
134+ safety_scores = np .vectorize (compute_safety_factor )(jerk , safe_thresh , unsafe_thresh )
135+
136+ axis .plot (time , jerk , color = "black" , linewidth = 0.8 , alpha = 0.5 )
137+ axis .scatter (time , jerk , c = safety_scores , cmap = CMAP , vmin = 0 , vmax = 1 , edgecolors = "black" )
138+
139+ axis .set_xlabel ("Time (s)" )
140+ axis .set_ylabel ("Jerk (m/s³)" )
141+ axis .set_title ("Vehicle Jerk Over Time" )
142+ axis .grid (True )
143+
144+ def plot_heading_acceleration (axis , time , heading_acc , safe_thresh = 0.0075 , unsafe_thresh = 0.25 ):
145+ """Plots vehicle heading acceleration vs. time"""
146+ safety_scores = np .vectorize (compute_safety_factor )(heading_acc , safe_thresh , unsafe_thresh )
147+
148+ axis .plot (time , heading_acc , color = "black" , linewidth = 0.8 , alpha = 0.5 )
149+ axis .scatter (time , heading_acc , c = safety_scores , cmap = CMAP , vmin = 0 , vmax = 1 , edgecolors = "black" )
150+
151+ axis .set_xlabel ("Time (s)" )
152+ axis .set_ylabel ("Heading Acceleration (rad/s²)" )
153+ axis .set_title ("Vehicle Heading Acceleration Over Time" )
154+ axis .grid (True )
155+
156+ def plot_crosstrack_error (axis , time , cte , safe_thresh = 0.1 , unsafe_thresh = 0.4 ):
157+ """Plots vehicle cross track error vs. time"""
158+ safety_scores = np .vectorize (compute_safety_factor )(cte , safe_thresh , unsafe_thresh )
159+
160+ axis .plot (time , cte , color = "black" , linewidth = 0.8 , alpha = 0.5 )
161+ axis .scatter (time , cte , c = safety_scores , cmap = CMAP , vmin = 0 , vmax = 1 , edgecolors = "black" )
162+
163+ axis .set_xlabel ("Time (s)" )
164+ axis .set_ylabel ("Cross Track Error" )
165+ axis .set_title ("Vehicle Cross Track Error Over Time" )
166+ axis .grid (True )
167+
168+ def plot_position (axis , x_actual , y_actual , x_desired , y_desired , safe_thresh = 1 , unsafe_thresh = 2.5 ):
169+ """Plots vehicle actual and desired positions vs. time"""
170+ position_error = np .sqrt ((x_desired - x_actual ) ** 2 + (y_desired - y_actual ) ** 2 )
171+ safety_scores = np .vectorize (compute_safety_factor )(position_error , safe_thresh , unsafe_thresh )
172+
173+ axis .plot (y_desired , x_desired , marker = '.' , linestyle = ':' , color = 'blue' , label = 'Desired' )
174+ axis .plot (y_actual , x_actual , color = "black" , linewidth = 0.8 , alpha = 0.5 )
175+ axis .scatter (y_actual , x_actual , c = safety_scores , cmap = CMAP , vmin = 0 , vmax = 1 , edgecolors = "black" )
176+
177+ axis .set_xlabel ("Y Position (m)" )
178+ axis .set_ylabel ("X Position (m)" )
179+ axis .set_title ("Vehicle Position vs. Desired Position" )
180+ axis .legend ()
181+ axis .grid (True )
182+
183+ def plot_pedestrian_dist (axis , pedestrian_times , pedestrian_distances , safe_thresh = 5.0 , unsafe_thresh = 2.0 ):
184+ """Plots pedestrian distance to vehicle vs. time"""
185+ if len (pedestrian_times ) > 0 :
186+ safety_scores = np .vectorize (compute_safety_factor )(pedestrian_distances , safe_thresh , unsafe_thresh , flip = True )
187+ axis .plot (pedestrian_times , pedestrian_distances , color = "black" , linewidth = 0.8 , alpha = 0.5 )
188+ axis .scatter (pedestrian_times , pedestrian_distances , c = safety_scores , cmap = CMAP , vmin = 0 , vmax = 1 , edgecolors = "black" )
189+
190+ axis .set_xlabel ("Time (s)" )
191+ axis .set_ylabel ("Pedestrian Distance (m)" )
192+ axis .set_title ("Pedestrian Distance Over Time" )
193+ axis .grid (True )
194+
195+ if __name__ == '__main__' :
196+ if len (sys .argv ) != 2 :
197+ print ("Usage: python test_comfort_metrics.py <log_directory>" )
198+ sys .exit (1 )
199+
200+ log_dir = sys .argv [1 ]
201+ behavior_file = os .path .join (log_dir , "behavior.json" )
202+ tracker_file = os .path .join (log_dir , "PurePursuitTrajectoryTracker_debug.csv" )
203+
204+ # if behavior.json doesn't exist, print error and exit
205+ if not os .path .exists (behavior_file ):
206+ print ("Error: behavior.json file is missing in log folder." )
207+ sys .exit (1 )
208+
209+ # Parse behavior log file and compute metrics
210+ times , accelerations , heading_rates , ped_times , ped_distances = parse_behavior_log (behavior_file )
211+ time_jerk , jerk = compute_derivative (times , accelerations )
212+ time_heading_acc , heading_acc = compute_derivative (times , heading_rates )
213+
214+ # Pure pursuit tracker file exists: parse and plot all metrics
215+ if os .path .exists (tracker_file ):
216+ vehicle_time , cte , x_actual , y_actual , x_desired , y_desired = parse_tracker_csv (tracker_file )
217+ plot_metrics (time_jerk , jerk , time_heading_acc , heading_acc , vehicle_time , cte ,
218+ x_actual , y_actual , x_desired , y_desired , ped_times , ped_distances )
219+
220+ print ("RMS Cross Track Error:" , np .sqrt (np .mean (cte ** 2 )), "m" )
221+ print ("RMS Position Error:" , np .sqrt (np .mean ((x_actual - x_desired )** 2 + (y_actual - y_desired )** 2 )), 'm' )
222+ # Pure pursuit tracker file is missing: plot only behavior.json metrics
223+ else :
224+ print ("Tracker file is missing. Skipping cross track error and vehicle position plots." )
225+ # Plot only jerk, heading acceleration, and pedestrian distance
226+ fig , axs = plt .subplots (1 , 3 , figsize = (12 , 4 ))
227+ plot_jerk (axs [0 ], time_jerk , jerk )
228+ plot_heading_acceleration (axs [1 ], time_heading_acc , heading_acc )
229+ plot_pedestrian_dist (axs [2 ], ped_times , ped_distances )
230+ add_safety_colorbar (fig )
231+ plt .show ()
232+
233+ print ("RMS Jerk:" , np .sqrt (np .mean (jerk ** 2 )), "m/s³" )
234+ print ("RMS Heading Acceleration:" , np .sqrt (np .mean (heading_acc ** 2 )), "rad/s²" )
235+ if len (ped_distances ) > 0 :
236+ print ("Minimum Pedestrian Distance:" , np .min (ped_distances ), "m" )
0 commit comments