Nav2 Navigation Stack - humble  humble
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 from geometry_msgs.msg import PoseStamped
17 from nav2_simple_commander.robot_navigator import BasicNavigator
18 import rclpy
19 from ament_index_python.packages import get_package_share_directory
20 
21 import math
22 import os
23 import pickle
24 import glob
25 import time
26 import numpy as np
27 
28 from random import seed
29 from random import randint
30 from random import uniform
31 
32 from transforms3d.euler import euler2quat
33 
34 
35 def getPlannerResults(navigator, initial_pose, goal_pose, planners):
36  results = []
37  for planner in planners:
38  path = navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=True)
39  if path is not None:
40  results.append(path)
41  else:
42  return results
43  return results
44 
45 
46 def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
47  start = PoseStamped()
48  start.header.frame_id = 'map'
49  start.header.stamp = time_stamp
50  while True:
51  row = randint(side_buffer, costmap.shape[0]-side_buffer)
52  col = randint(side_buffer, costmap.shape[1]-side_buffer)
53 
54  if costmap[row, col] < max_cost:
55  start.pose.position.x = col*res
56  start.pose.position.y = row*res
57 
58  yaw = uniform(0, 1) * 2*math.pi
59  quad = euler2quat(0.0, 0.0, yaw)
60  start.pose.orientation.w = quad[0]
61  start.pose.orientation.x = quad[1]
62  start.pose.orientation.y = quad[2]
63  start.pose.orientation.z = quad[3]
64  break
65  return start
66 
67 
68 def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
69  goal = PoseStamped()
70  goal.header.frame_id = 'map'
71  goal.header.stamp = time_stamp
72  while True:
73  row = randint(side_buffer, costmap.shape[0]-side_buffer)
74  col = randint(side_buffer, costmap.shape[1]-side_buffer)
75 
76  start_x = start.pose.position.x
77  start_y = start.pose.position.y
78  goal_x = col*res
79  goal_y = row*res
80  x_diff = goal_x - start_x
81  y_diff = goal_y - start_y
82  dist = math.sqrt(x_diff ** 2 + y_diff ** 2)
83 
84  if costmap[row, col] < max_cost and dist > 3.0:
85  goal.pose.position.x = goal_x
86  goal.pose.position.y = goal_y
87 
88  yaw = uniform(0, 1) * 2*math.pi
89  quad = euler2quat(0.0, 0.0, yaw)
90  goal.pose.orientation.w = quad[0]
91  goal.pose.orientation.x = quad[1]
92  goal.pose.orientation.y = quad[2]
93  goal.pose.orientation.z = quad[3]
94  break
95  return goal
96 
97 
98 def main():
99  rclpy.init()
100 
101  navigator = BasicNavigator()
102 
103  # Set map to use, other options: 100by100_15, 100by100_10
104  map_path = os.getcwd() + '/' + glob.glob('**/100by100_20.yaml', recursive=True)[0]
105  navigator.changeMap(map_path)
106  time.sleep(2)
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  planners = ['Navfn', 'ThetaStar', 'SmacHybrid', 'Smac2d', 'SmacLattice']
114  max_cost = 210
115  side_buffer = 100
116  time_stamp = navigator.get_clock().now().to_msg()
117  results = []
118  seed(33)
119 
120  random_pairs = 100
121  res = costmap_msg.metadata.resolution
122  i = 0
123  while len(results) != random_pairs:
124  print("Cycle: ", i, "out of: ", random_pairs)
125  start = getRandomStart(costmap, max_cost, side_buffer, time_stamp, res)
126  goal = getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res)
127  print("Start", start)
128  print("Goal", goal)
129  result = getPlannerResults(navigator, start, goal, planners)
130  if len(result) == len(planners):
131  results.append(result)
132  i = i + 1
133  else:
134  print("One of the planners was invalid")
135 
136  print("Write Results...")
137  with open(os.getcwd() + '/results.pickle', 'wb+') as f:
138  pickle.dump(results, f, pickle.HIGHEST_PROTOCOL)
139 
140  with open(os.getcwd() + '/costmap.pickle', 'wb+') as f:
141  pickle.dump(costmap_msg, f, pickle.HIGHEST_PROTOCOL)
142 
143  with open(os.getcwd() + '/planners.pickle', 'wb+') as f:
144  pickle.dump(planners, f, pickle.HIGHEST_PROTOCOL)
145  print("Write Complete")
146  exit(0)
147 
148 
149 if __name__ == '__main__':
150  main()