Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
process_data.py
1 #! /usr/bin/env python3
2 # Copyright (c) 2022 Samsung R&D Institute Russia
3 # Copyright (c) 2022 Joshua Wallace
4 # Copyright (c) 2021 RoboTech Vision
5 #
6 # Licensed under the Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import math
19 import os
20 import pickle
21 
22 import matplotlib.pylab as plt
23 import numpy as np
24 import seaborn as sns
25 from tabulate import tabulate
26 
27 
28 def getPaths(results):
29  paths = []
30  for i in range(len(results)):
31  if (i % 2) == 0:
32  # Append non-smoothed path
33  paths.append(results[i].path)
34  else:
35  # Append smoothed paths array
36  for result in results[i]:
37  paths.append(result.path)
38  return paths
39 
40 
41 def getTimes(results):
42  times = []
43  for i in range(len(results)):
44  if (i % 2) == 0:
45  # Append non-smoothed time
46  times.append(
47  results[i].planning_time.nanosec / 1e09 + results[i].planning_time.sec
48  )
49  else:
50  # Append smoothed times array
51  for result in results[i]:
52  times.append(
53  result.smoothing_duration.nanosec / 1e09
54  + result.smoothing_duration.sec
55  )
56  return times
57 
58 
59 def getMapCoordsFromPaths(paths, resolution):
60  coords = []
61  for path in paths:
62  x = []
63  y = []
64  for pose in path.poses:
65  x.append(pose.pose.position.x / resolution)
66  y.append(pose.pose.position.y / resolution)
67  coords.append(x)
68  coords.append(y)
69  return coords
70 
71 
72 def getPathLength(path):
73  path_length = 0
74  x_prev = path.poses[0].pose.position.x
75  y_prev = path.poses[0].pose.position.y
76  for i in range(1, len(path.poses)):
77  x_curr = path.poses[i].pose.position.x
78  y_curr = path.poses[i].pose.position.y
79  path_length = path_length + math.sqrt(
80  (x_curr - x_prev) ** 2 + (y_curr - y_prev) ** 2
81  )
82  x_prev = x_curr
83  y_prev = y_curr
84  return path_length
85 
86 
87 # Path smoothness calculations
88 def getSmoothness(pt_prev, pt, pt_next):
89  d1 = pt - pt_prev
90  d2 = pt_next - pt
91  delta = d2 - d1
92  return np.linalg.norm(delta)
93 
94 
95 def getPathSmoothnesses(paths):
96  smoothnesses = []
97  pm0 = np.array([0.0, 0.0])
98  pm1 = np.array([0.0, 0.0])
99  pm2 = np.array([0.0, 0.0])
100  for path in paths:
101  smoothness = 0.0
102  for i in range(2, len(path.poses)):
103  pm0[0] = path.poses[i].pose.position.x
104  pm0[1] = path.poses[i].pose.position.y
105  pm1[0] = path.poses[i - 1].pose.position.x
106  pm1[1] = path.poses[i - 1].pose.position.y
107  pm2[0] = path.poses[i - 2].pose.position.x
108  pm2[1] = path.poses[i - 2].pose.position.y
109  smoothness += getSmoothness(pm2, pm1, pm0)
110  smoothnesses.append(smoothness)
111  return smoothnesses
112 
113 
114 # Curvature calculations
115 def arcCenter(pt_prev, pt, pt_next):
116  cusp_thresh = -0.7
117 
118  d1 = pt - pt_prev
119  d2 = pt_next - pt
120 
121  d1_norm = d1 / np.linalg.norm(d1)
122  d2_norm = d2 / np.linalg.norm(d2)
123  cos_angle = np.dot(d1_norm, d2_norm)
124 
125  if cos_angle < cusp_thresh:
126  # cusp case
127  d2 = -d2
128  pt_next = pt + d2
129 
130  det = d1[0] * d2[1] - d1[1] * d2[0]
131  if abs(det) < 1e-4: # straight line
132  return (float('inf'), float('inf'))
133 
134  # circle center is at the intersection of mirror axes of the segments:
135  # http://paulbourke.net/geometry/circlesphere/
136  # line intersection:
137  # https://en.wikipedia.org/wiki/Line%E2%80%93line_intersection#Intersection%20of%20two%20lines
138  mid1 = (pt_prev + pt) / 2
139  mid2 = (pt + pt_next) / 2
140  n1 = (-d1[1], d1[0])
141  n2 = (-d2[1], d2[0])
142  det1 = (mid1[0] + n1[0]) * mid1[1] - (mid1[1] + n1[1]) * mid1[0]
143  det2 = (mid2[0] + n2[0]) * mid2[1] - (mid2[1] + n2[1]) * mid2[0]
144  center = np.array(
145  [(det1 * n2[0] - det2 * n1[0]) / det, (det1 * n2[1] - det2 * n1[1]) / det]
146  )
147  return center
148 
149 
150 def getPathCurvatures(paths):
151  curvatures = []
152  pm0 = np.array([0.0, 0.0])
153  pm1 = np.array([0.0, 0.0])
154  pm2 = np.array([0.0, 0.0])
155  for path in paths:
156  radiuses = []
157  for i in range(2, len(path.poses)):
158  pm0[0] = path.poses[i].pose.position.x
159  pm0[1] = path.poses[i].pose.position.y
160  pm1[0] = path.poses[i - 1].pose.position.x
161  pm1[1] = path.poses[i - 1].pose.position.y
162  pm2[0] = path.poses[i - 2].pose.position.x
163  pm2[1] = path.poses[i - 2].pose.position.y
164  center = arcCenter(pm2, pm1, pm0)
165  if center[0] != float('inf'):
166  turning_rad = np.linalg.norm(pm1 - center)
167  radiuses.append(turning_rad)
168  curvatures.append(np.average(radiuses))
169  return curvatures
170 
171 
172 def plotResults(costmap, paths):
173  coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
174  data = np.asarray(costmap.data)
175  data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
176  data = np.where(data <= 253, 0, data)
177 
178  plt.figure(3)
179  ax = sns.heatmap(data, cmap='Greys', cbar=False)
180  for i in range(0, len(coords), 2):
181  ax.plot(coords[i], coords[i + 1], linewidth=0.7)
182  plt.axis('off')
183  ax.set_aspect('equal', 'box')
184  plt.show()
185 
186 
187 def averagePathCost(paths, costmap, num_of_planners):
188  coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
189  data = np.asarray(costmap.data)
190  data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
191 
192  average_path_costs = []
193  for i in range(num_of_planners):
194  average_path_costs.append([])
195 
196  k = 0
197  for i in range(0, len(coords), 2):
198  costs = []
199  for j in range(len(coords[i])):
200  costs.append(data[math.floor(coords[i + 1][j])][math.floor(coords[i][j])])
201  average_path_costs[k % num_of_planners].append(sum(costs) / len(costs))
202  k += 1
203 
204  return average_path_costs
205 
206 
207 def maxPathCost(paths, costmap, num_of_planners):
208  coords = getMapCoordsFromPaths(paths, costmap.metadata.resolution)
209  data = np.asarray(costmap.data)
210  data.resize(costmap.metadata.size_y, costmap.metadata.size_x)
211 
212  max_path_costs = []
213  for i in range(num_of_planners):
214  max_path_costs.append([])
215 
216  k = 0
217  for i in range(0, len(coords), 2):
218  max_cost = 0
219  for j in range(len(coords[i])):
220  cost = data[math.floor(coords[i + 1][j])][math.floor(coords[i][j])]
221  if max_cost < cost:
222  max_cost = cost
223  max_path_costs[k % num_of_planners].append(max_cost)
224  k += 1
225 
226  return max_path_costs
227 
228 
229 def main():
230  # Read the data
231  benchmark_dir = os.getcwd()
232  print('Read data')
233  with open(os.path.join(benchmark_dir, 'results.pickle'), 'rb') as f:
234  results = pickle.load(f)
235 
236  with open(os.path.join(benchmark_dir, 'methods.pickle'), 'rb') as f:
237  smoothers = pickle.load(f)
238  planner = smoothers[0]
239  del smoothers[0]
240  methods_num = len(smoothers) + 1
241 
242  with open(os.path.join(benchmark_dir, 'costmap.pickle'), 'rb') as f:
243  costmap = pickle.load(f)
244 
245  # Paths (planner and smoothers)
246  paths = getPaths(results)
247  path_lengths = []
248 
249  for path in paths:
250  path_lengths.append(getPathLength(path))
251  path_lengths = np.asarray(path_lengths)
252  total_paths = len(paths)
253 
254  # [planner, smoothers] path lenghth in a row
255  path_lengths.resize((int(total_paths / methods_num), methods_num))
256  # [planner, smoothers] path length in a column
257  path_lengths = path_lengths.transpose()
258 
259  # Times
260  times = getTimes(results)
261  times = np.asarray(times)
262  times.resize((int(total_paths / methods_num), methods_num))
263  times = np.transpose(times)
264 
265  # Costs
266  average_path_costs = np.asarray(averagePathCost(paths, costmap, methods_num))
267  max_path_costs = np.asarray(maxPathCost(paths, costmap, methods_num))
268 
269  # Smoothness
270  smoothnesses = getPathSmoothnesses(paths)
271  smoothnesses = np.asarray(smoothnesses)
272  smoothnesses.resize((int(total_paths / methods_num), methods_num))
273  smoothnesses = np.transpose(smoothnesses)
274 
275  # Curvatures
276  curvatures = getPathCurvatures(paths)
277  curvatures = np.asarray(curvatures)
278  curvatures.resize((int(total_paths / methods_num), methods_num))
279  curvatures = np.transpose(curvatures)
280 
281  # Generate table
282  planner_table = [
283  [
284  'Planner',
285  'Time (s)',
286  'Path length (m)',
287  'Average cost',
288  'Max cost',
289  'Path smoothness (x100)',
290  'Average turning rad (m)',
291  ]
292  ]
293  # for path planner
294  planner_table.append(
295  [
296  planner,
297  np.average(times[0]),
298  np.average(path_lengths[0]),
299  np.average(average_path_costs[0]),
300  np.average(max_path_costs[0]),
301  np.average(smoothnesses[0]) * 100,
302  np.average(curvatures[0]),
303  ]
304  )
305  # for path smoothers
306  for i in range(1, methods_num):
307  planner_table.append(
308  [
309  smoothers[i - 1],
310  np.average(times[i]),
311  np.average(path_lengths[i]),
312  np.average(average_path_costs[i]),
313  np.average(max_path_costs[i]),
314  np.average(smoothnesses[i]) * 100,
315  np.average(curvatures[i]),
316  ]
317  )
318 
319  # Visualize results
320  print(tabulate(planner_table))
321  plotResults(costmap, paths)
322 
323  exit(0)
324 
325 
326 if __name__ == '__main__':
327  main()