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