Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
metrics.py
1 #! /usr/bin/env python3
2 # Copyright (c) 2022 Samsung R&D Institute Russia
3 # Copyright (c) 2022 Joshua Wallace
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 from geometry_msgs.msg import PoseStamped
18 from nav2_simple_commander.robot_navigator import BasicNavigator
19 import rclpy
20 
21 import math
22 import os
23 import pickle
24 import numpy as np
25 
26 from random import seed
27 from random import randint
28 from random import uniform
29 
30 from transforms3d.euler import euler2quat
31 
32 
33 # Note: Map origin is assumed to be (0,0)
34 
35 def getPlannerResults(navigator, initial_pose, goal_pose, planner):
36  return navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=True)
37 
38 def getSmootherResults(navigator, path, smoothers):
39  smoothed_results = []
40  for smoother in smoothers:
41  smoothed_result = navigator._smoothPathImpl(path, smoother)
42  if smoothed_result is not None:
43  smoothed_results.append(smoothed_result)
44  else:
45  print(smoother, " failed to smooth the path")
46  return None
47  return smoothed_results
48 
49 def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
50  start = PoseStamped()
51  start.header.frame_id = 'map'
52  start.header.stamp = time_stamp
53  while True:
54  row = randint(side_buffer, costmap.shape[0]-side_buffer)
55  col = randint(side_buffer, costmap.shape[1]-side_buffer)
56 
57  if costmap[row, col] < max_cost:
58  start.pose.position.x = col*res
59  start.pose.position.y = row*res
60 
61  yaw = uniform(0, 1) * 2*math.pi
62  quad = euler2quat(0.0, 0.0, yaw)
63  start.pose.orientation.w = quad[0]
64  start.pose.orientation.x = quad[1]
65  start.pose.orientation.y = quad[2]
66  start.pose.orientation.z = quad[3]
67  break
68  return start
69 
70 def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
71  goal = PoseStamped()
72  goal.header.frame_id = 'map'
73  goal.header.stamp = time_stamp
74  while True:
75  row = randint(side_buffer, costmap.shape[0]-side_buffer)
76  col = randint(side_buffer, costmap.shape[1]-side_buffer)
77 
78  start_x = start.pose.position.x
79  start_y = start.pose.position.y
80  goal_x = col*res
81  goal_y = row*res
82  x_diff = goal_x - start_x
83  y_diff = goal_y - start_y
84  dist = math.sqrt(x_diff ** 2 + y_diff ** 2)
85 
86  if costmap[row, col] < max_cost and dist > 3.0:
87  goal.pose.position.x = goal_x
88  goal.pose.position.y = goal_y
89 
90  yaw = uniform(0, 1) * 2*math.pi
91  quad = euler2quat(0.0, 0.0, yaw)
92  goal.pose.orientation.w = quad[0]
93  goal.pose.orientation.x = quad[1]
94  goal.pose.orientation.y = quad[2]
95  goal.pose.orientation.z = quad[3]
96  break
97  return goal
98 
99 def main():
100  rclpy.init()
101 
102  navigator = BasicNavigator()
103 
104  # Wait for planner and smoother to fully activate
105  print("Waiting for planner and smoother servers to activate")
106  navigator.waitUntilNav2Active('smoother_server', 'planner_server')
107 
108  # Get the costmap for start/goal validation
109  costmap_msg = navigator.getGlobalCostmap()
110  costmap = np.asarray(costmap_msg.data)
111  costmap.resize(costmap_msg.metadata.size_y, costmap_msg.metadata.size_x)
112 
113  planner = 'SmacHybrid'
114  smoothers = ['simple_smoother', 'constrained_smoother']
115  max_cost = 210
116  side_buffer = 10
117  time_stamp = navigator.get_clock().now().to_msg()
118  results = []
119  seed(33)
120 
121  random_pairs = 100
122  i = 0
123  res = costmap_msg.metadata.resolution
124  while i < random_pairs:
125  print("Cycle: ", i, "out of: ", random_pairs)
126  start = getRandomStart(costmap, max_cost, side_buffer, time_stamp, res)
127  goal = getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res)
128  print("Start", start)
129  print("Goal", goal)
130  result = getPlannerResults(navigator, start, goal, planner)
131  if result is not None:
132  smoothed_results = getSmootherResults(navigator, result.path, smoothers)
133  if smoothed_results is not None:
134  results.append(result)
135  results.append(smoothed_results)
136  i += 1
137  else:
138  print(planner, " planner failed to produce the path")
139 
140  print("Write Results...")
141  benchmark_dir = os.getcwd()
142  with open(os.path.join(benchmark_dir, 'results.pickle'), 'wb') as f:
143  pickle.dump(results, f, pickle.HIGHEST_PROTOCOL)
144 
145  with open(os.path.join(benchmark_dir, 'costmap.pickle'), 'wb') as f:
146  pickle.dump(costmap_msg, f, pickle.HIGHEST_PROTOCOL)
147 
148  smoothers.insert(0, planner)
149  with open(os.path.join(benchmark_dir, 'methods.pickle'), 'wb') as f:
150  pickle.dump(smoothers, f, pickle.HIGHEST_PROTOCOL)
151  print("Write Complete")
152 
153  exit(0)
154 
155 
156 if __name__ == '__main__':
157  main()