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