20 from random
import randint, seed, uniform
21 from typing
import Optional
25 from nav2_msgs.action
import ComputePathToPose, SmoothPath
28 from numpy.typing
import NDArray
30 from transforms3d.euler
import euler2quat
35 def getPlannerResults(
36 navigator: BasicNavigator, initial_pose: PoseStamped,
37 goal_pose: PoseStamped, planner: str) -> Optional[ComputePathToPose.Result]:
38 result = navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=
True)
39 if result
is None or result.error_code != 0:
40 print(planner,
'planner failed to produce the path')
45 def getSmootherResults(
46 navigator: BasicNavigator, path: PoseStamped,
47 smoothers: list[str]) -> Optional[list[SmoothPath.Result]]:
49 for smoother
in smoothers:
50 smoothed_result = navigator._smoothPathImpl(path, smoother)
51 if smoothed_result
is not None:
52 smoothed_results.append(smoothed_result)
54 print(smoother,
'failed to smooth the path')
56 return smoothed_results
59 def getRandomStart(costmap: NDArray[np.float32], max_cost: int,
60 side_buffer: int, time_stamp: Time, res: float) -> PoseStamped:
62 start.header.frame_id =
'map'
63 start.header.stamp = time_stamp
65 row = randint(side_buffer, costmap.shape[0] - side_buffer)
66 col = randint(side_buffer, costmap.shape[1] - side_buffer)
68 if costmap[row, col] < max_cost:
69 start.pose.position.x = col * res
70 start.pose.position.y = row * res
72 yaw = uniform(0, 1) * 2 * math.pi
73 quad = euler2quat(0.0, 0.0, yaw)
74 start.pose.orientation.w = quad[0]
75 start.pose.orientation.x = quad[1]
76 start.pose.orientation.y = quad[2]
77 start.pose.orientation.z = quad[3]
83 costmap: NDArray[np.float32], start: PoseStamped,
84 max_cost: int, side_buffer: int,
85 time_stamp: Time, res: float) -> PoseStamped:
87 goal.header.frame_id =
'map'
88 goal.header.stamp = time_stamp
90 row = randint(side_buffer, costmap.shape[0] - side_buffer)
91 col = randint(side_buffer, costmap.shape[1] - side_buffer)
93 start_x = start.pose.position.x
94 start_y = start.pose.position.y
97 x_diff = goal_x - start_x
98 y_diff = goal_y - start_y
99 dist = math.sqrt(x_diff ** 2 + y_diff ** 2)
101 if costmap[row, col] < max_cost
and dist > 3.0:
102 goal.pose.position.x = goal_x
103 goal.pose.position.y = goal_y
105 yaw = uniform(0, 1) * 2 * math.pi
106 quad = euler2quat(0.0, 0.0, yaw)
107 goal.pose.orientation.w = quad[0]
108 goal.pose.orientation.x = quad[1]
109 goal.pose.orientation.y = quad[2]
110 goal.pose.orientation.z = quad[3]
118 navigator = BasicNavigator()
121 print(
'Waiting for planner and smoother servers to activate')
122 navigator.waitUntilNav2Active(
'smoother_server',
'planner_server')
125 costmap_msg = navigator.getGlobalCostmap()
126 costmap = np.asarray(costmap_msg.data)
127 costmap.resize(costmap_msg.metadata.size_y, costmap_msg.metadata.size_x)
129 planner =
'SmacHybrid'
130 smoothers = [
'simple_smoother',
'constrained_smoother',
'sg_smoother']
133 time_stamp = navigator.get_clock().now().to_msg()
139 res = costmap_msg.metadata.resolution
140 while i < random_pairs:
141 print(
'Cycle: ', i,
'out of: ', random_pairs)
142 start = getRandomStart(costmap, max_cost, side_buffer, time_stamp, res)
143 goal = getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res)
144 print(
'Start', start)
146 result = getPlannerResults(navigator, start, goal, planner)
147 if result
is not None:
148 smoothed_results = getSmootherResults(navigator, result.path, smoothers)
149 if smoothed_results
is not None:
150 results.append(result)
151 results.append(smoothed_results)
154 print(
'Write Results...')
155 benchmark_dir = os.getcwd()
156 with open(os.path.join(benchmark_dir,
'results.pickle'),
'wb')
as f:
157 pickle.dump(results, f, pickle.HIGHEST_PROTOCOL)
159 with open(os.path.join(benchmark_dir,
'costmap.pickle'),
'wb')
as f:
160 pickle.dump(costmap_msg, f, pickle.HIGHEST_PROTOCOL)
162 smoothers.insert(0, planner)
163 with open(os.path.join(benchmark_dir,
'methods.pickle'),
'wb')
as f:
164 pickle.dump(smoothers, f, pickle.HIGHEST_PROTOCOL)
165 print(
'Write Complete')
170 if __name__ ==
'__main__':