Skip to content

Commit ec5c28c

Browse files
authored
Add files via upload
1 parent 0ed85b3 commit ec5c28c

2 files changed

Lines changed: 239 additions & 0 deletions

File tree

logs/logplot_pp.py

Lines changed: 120 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
####Following code can be used to visualize performance of Pure Pursuit after using it.###
2+
###How to use?- After running the simulation or on actual vehicle you get logs in log folder###
3+
### You can run the command- python3 logplot_pp.py "logfilename".###
4+
5+
6+
import json
7+
import sys
8+
import os
9+
import matplotlib.pyplot as plt
10+
import numpy as np
11+
12+
# Safety thresholds (not used in the current plots)
13+
ACC_SAFE = 0.8 # |acceleration| <= 0.8 m/s² is safe
14+
ACC_UNSAFE = 2.0 # |acceleration| >= 2.0 m/s² is unsafe
15+
HR_SAFE = 0.05 # |heading_rate| <= 0.05 rad/s is safe
16+
HR_UNSAFE = 0.2 # |heading_rate| >= 0.2 rad/s is unsafe
17+
18+
def parse_behavior_log(filename):
19+
times = []
20+
accelerations = []
21+
heading_rates = []
22+
23+
with open(filename, 'r') as f:
24+
first_time = None # Store the first timestamp for shifting
25+
for line in f:
26+
try:
27+
entry = json.loads(line)
28+
except json.JSONDecodeError:
29+
print(f"Skipping invalid JSON line: {line.strip()}")
30+
continue
31+
if "vehicle" in entry:
32+
t = entry.get("time")
33+
vehicle_data = entry["vehicle"].get("data", {})
34+
acceleration = vehicle_data.get("acceleration")
35+
heading_rate = vehicle_data.get("heading_rate")
36+
if t is not None and acceleration is not None and heading_rate is not None:
37+
if first_time is None:
38+
first_time = t # Set the first timestamp
39+
times.append(t - first_time) # Shift time to start from 0
40+
accelerations.append(acceleration)
41+
heading_rates.append(heading_rate)
42+
43+
return np.array(times), np.array(accelerations), np.array(heading_rates)
44+
45+
def parse_tracker_csv(filename):
46+
data = np.genfromtxt(filename, delimiter=',', skip_header=1)
47+
first_time = data[0, 18] # Normalize time to start from 0
48+
cte_time = data[:, 18] - first_time
49+
cte = data[:, 20]
50+
x_actual, y_actual = data[:, 2], data[:, 5]
51+
x_desired, y_desired = data[:, 11], data[:, 14]
52+
return cte_time, cte, x_actual, y_actual, x_desired, y_desired
53+
54+
def compute_derivative(times, values):
55+
dt = np.diff(times)
56+
dv = np.diff(values)
57+
derivative = dv / dt
58+
return times[1:], derivative
59+
60+
def plot_metrics(time_jerk, jerk, time_heading_acc, heading_acc, cte_time, cte, x_actual, y_actual, x_desired, y_desired):
61+
global_min_time = min(time_jerk[0], time_heading_acc[0], cte_time[0])
62+
global_max_time = max(time_jerk[-1], time_heading_acc[-1], cte_time[-1])
63+
64+
fig, axs = plt.subplots(2, 2, figsize=(12, 8))
65+
fig.subplots_adjust(hspace=0.4, wspace=0.3)
66+
67+
axs[0,0].plot(time_jerk, jerk, marker='', linestyle='-', color='blue')
68+
axs[0,0].set_ylabel("Jerk (m/s³)")
69+
axs[0,0].set_title("Vehicle Jerk Over Time")
70+
axs[0,0].grid(True)
71+
axs[0,0].set_xlim(global_min_time, global_max_time)
72+
73+
axs[0,1].plot(time_heading_acc, heading_acc, marker='', linestyle='-', color='orange')
74+
axs[0,1].set_ylabel("Heading Acceleration (rad/s²)")
75+
axs[0,1].set_title("Vehicle Heading Acceleration Over Time")
76+
axs[0,1].grid(True)
77+
axs[0,1].set_xlim(global_min_time, global_max_time)
78+
79+
axs[1,0].plot(cte_time, cte, marker='', linestyle='-', color='green')
80+
axs[1,0].set_xlabel("Time (s)")
81+
axs[1,0].set_ylabel("Cross Track Error")
82+
axs[1,0].set_title("Vehicle Cross Track Error Over Time")
83+
axs[1,0].grid(True)
84+
axs[1,0].set_xlim(global_min_time, global_max_time)
85+
86+
axs[1,1].plot(x_actual, y_actual, marker='', linestyle='-', color='blue', label='Actual')
87+
axs[1,1].plot(x_desired, y_desired, marker='', linestyle='-', color='orange', label='Desired')
88+
axs[1,1].set_xlabel("X Position (m)")
89+
axs[1,1].set_ylabel("Y Position (m)")
90+
axs[1,1].set_title("Vehicle Position")
91+
axs[1,1].legend()
92+
axs[1,1].grid(True)
93+
94+
plt.show()
95+
96+
if __name__=='__main__':
97+
if len(sys.argv) != 2:
98+
print("Usage: python test_comfort_metrics.py <log_directory>")
99+
sys.exit(1)
100+
101+
log_dir = sys.argv[1]
102+
behavior_file = os.path.join(log_dir, "behavior.json")
103+
tracker_file = os.path.join(log_dir, "PurePursuitTrajectoryTracker_debug.csv")
104+
#tracker_file = os.path.join(log_dir, "StanleyTrajectoryTracker_debug.csv")
105+
106+
times, accelerations, heading_rates = parse_behavior_log(behavior_file)
107+
time_jerk, jerk = compute_derivative(times, accelerations)
108+
time_heading_acc, heading_acc = compute_derivative(times, heading_rates)
109+
110+
cte_time, cte, x_actual, y_actual, x_desired, y_desired = parse_tracker_csv(tracker_file)
111+
112+
plot_metrics(time_jerk, jerk, time_heading_acc, heading_acc, cte_time, cte, x_actual, y_actual, x_desired, y_desired)
113+
114+
print("Max (abs) jerk:", np.max(np.abs(jerk)))
115+
print("Avg jerk:", np.mean(np.abs(jerk)))
116+
print("Max (abs) heading acceleration:", np.max(np.abs(heading_acc)))
117+
print("Avg heading acceleration:", np.mean(np.abs(heading_acc)))
118+
print("Max (abs) cross track error:", np.max(np.abs(cte)))
119+
print("Avg cross track error:", np.mean(np.abs(cte)))
120+

logs/logplot_s.py

Lines changed: 119 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,119 @@
1+
####Following code can be used to visualize performance of Stanley after using it.###
2+
###How to use?- After running the simulation or on actual vehicle you get logs in log folder###
3+
### You can run the command- python3 logplot_s.py "logfilename".###
4+
5+
import json
6+
import sys
7+
import os
8+
import matplotlib.pyplot as plt
9+
import numpy as np
10+
11+
# Safety thresholds (not used in the current plots)
12+
ACC_SAFE = 0.8 # |acceleration| <= 0.8 m/s² is safe
13+
ACC_UNSAFE = 2.0 # |acceleration| >= 2.0 m/s² is unsafe
14+
HR_SAFE = 0.05 # |heading_rate| <= 0.05 rad/s is safe
15+
HR_UNSAFE = 0.2 # |heading_rate| >= 0.2 rad/s is unsafe
16+
17+
def parse_behavior_log(filename):
18+
times = []
19+
accelerations = []
20+
heading_rates = []
21+
22+
with open(filename, 'r') as f:
23+
first_time = None # Store the first timestamp for shifting
24+
for line in f:
25+
try:
26+
entry = json.loads(line)
27+
except json.JSONDecodeError:
28+
print(f"Skipping invalid JSON line: {line.strip()}")
29+
continue
30+
if "vehicle" in entry:
31+
t = entry.get("time")
32+
vehicle_data = entry["vehicle"].get("data", {})
33+
acceleration = vehicle_data.get("acceleration")
34+
heading_rate = vehicle_data.get("heading_rate")
35+
if t is not None and acceleration is not None and heading_rate is not None:
36+
if first_time is None:
37+
first_time = t # Set the first timestamp
38+
times.append(t - first_time) # Shift time to start from 0
39+
accelerations.append(acceleration)
40+
heading_rates.append(heading_rate)
41+
42+
return np.array(times), np.array(accelerations), np.array(heading_rates)
43+
44+
def parse_tracker_csv(filename):
45+
data = np.genfromtxt(filename, delimiter=',', skip_header=1)
46+
first_time = data[0, 18] # Normalize time to start from 0
47+
cte_time = data[:, 18] - first_time
48+
cte = data[:, 20]
49+
x_actual, y_actual = data[:, 2], data[:, 5]
50+
x_desired, y_desired = data[:, 8], data[:, 11]
51+
return cte_time, cte, x_actual, y_actual, x_desired, y_desired
52+
53+
def compute_derivative(times, values):
54+
dt = np.diff(times)
55+
dv = np.diff(values)
56+
derivative = dv / dt
57+
return times[1:], derivative
58+
59+
def plot_metrics(time_jerk, jerk, time_heading_acc, heading_acc, cte_time, cte, x_actual, y_actual, x_desired, y_desired):
60+
global_min_time = min(time_jerk[0], time_heading_acc[0], cte_time[0])
61+
global_max_time = max(time_jerk[-1], time_heading_acc[-1], cte_time[-1])
62+
63+
fig, axs = plt.subplots(2, 2, figsize=(12, 8))
64+
fig.subplots_adjust(hspace=0.4, wspace=0.3)
65+
66+
axs[0,0].plot(time_jerk, jerk, marker='', linestyle='-', color='blue')
67+
axs[0,0].set_ylabel("Jerk (m/s³)")
68+
axs[0,0].set_title("Vehicle Jerk Over Time")
69+
axs[0,0].grid(True)
70+
axs[0,0].set_xlim(global_min_time, global_max_time)
71+
72+
axs[0,1].plot(time_heading_acc, heading_acc, marker='', linestyle='-', color='orange')
73+
axs[0,1].set_ylabel("Heading Acceleration (rad/s²)")
74+
axs[0,1].set_title("Vehicle Heading Acceleration Over Time")
75+
axs[0,1].grid(True)
76+
axs[0,1].set_xlim(global_min_time, global_max_time)
77+
78+
axs[1,0].plot(cte_time, cte, marker='', linestyle='-', color='green')
79+
axs[1,0].set_xlabel("Time (s)")
80+
axs[1,0].set_ylabel("Cross Track Error")
81+
axs[1,0].set_title("Vehicle Cross Track Error Over Time")
82+
axs[1,0].grid(True)
83+
axs[1,0].set_xlim(global_min_time, global_max_time)
84+
85+
axs[1,1].plot(x_actual, y_actual, marker='', linestyle='-', color='blue', label='Actual')
86+
axs[1,1].plot(x_desired, y_desired, marker='', linestyle='-', color='orange', label='Desired')
87+
axs[1,1].set_xlabel("X Position (m)")
88+
axs[1,1].set_ylabel("Y Position (m)")
89+
axs[1,1].set_title("Vehicle Position")
90+
axs[1,1].legend()
91+
axs[1,1].grid(True)
92+
93+
plt.show()
94+
95+
if __name__=='__main__':
96+
if len(sys.argv) != 2:
97+
print("Usage: python test_comfort_metrics.py <log_directory>")
98+
sys.exit(1)
99+
100+
log_dir = sys.argv[1]
101+
behavior_file = os.path.join(log_dir, "behavior.json")
102+
#tracker_file = os.path.join(log_dir, "PurePursuitTrajectoryTracker_debug.csv")
103+
tracker_file = os.path.join(log_dir, "StanleyTrajectoryTracker_debug.csv")
104+
105+
times, accelerations, heading_rates = parse_behavior_log(behavior_file)
106+
time_jerk, jerk = compute_derivative(times, accelerations)
107+
time_heading_acc, heading_acc = compute_derivative(times, heading_rates)
108+
109+
cte_time, cte, x_actual, y_actual, x_desired, y_desired = parse_tracker_csv(tracker_file)
110+
111+
plot_metrics(time_jerk, jerk, time_heading_acc, heading_acc, cte_time, cte, x_actual, y_actual, x_desired, y_desired)
112+
113+
print("Max (abs) jerk:", np.max(np.abs(jerk)))
114+
print("Avg jerk:", np.mean(np.abs(jerk)))
115+
print("Max (abs) heading acceleration:", np.max(np.abs(heading_acc)))
116+
print("Avg heading acceleration:", np.mean(np.abs(heading_acc)))
117+
print("Max (abs) cross track error:", np.max(np.abs(cte)))
118+
print("Avg cross track error:", np.mean(np.abs(cte)))
119+

0 commit comments

Comments
 (0)