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