20 from random
import randint, seed, uniform
22 from geometry_msgs.msg
import PoseStamped
26 from transforms3d.euler
import euler2quat
32 def getPlannerResults(navigator, initial_pose, goal_pose, planner):
33 result = navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=
True)
34 if result
is None or result.error_code != 0:
35 print(planner,
'planner failed to produce the path')
40 def getSmootherResults(navigator, path, smoothers):
42 for smoother
in smoothers:
43 smoothed_result = navigator._smoothPathImpl(path, smoother)
44 if smoothed_result
is not None:
45 smoothed_results.append(smoothed_result)
47 print(smoother,
'failed to smooth the path')
49 return smoothed_results
52 def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
54 start.header.frame_id =
'map'
55 start.header.stamp = time_stamp
57 row = randint(side_buffer, costmap.shape[0] - side_buffer)
58 col = randint(side_buffer, costmap.shape[1] - side_buffer)
60 if costmap[row, col] < max_cost:
61 start.pose.position.x = col * res
62 start.pose.position.y = row * res
64 yaw = uniform(0, 1) * 2 * math.pi
65 quad = euler2quat(0.0, 0.0, yaw)
66 start.pose.orientation.w = quad[0]
67 start.pose.orientation.x = quad[1]
68 start.pose.orientation.y = quad[2]
69 start.pose.orientation.z = quad[3]
74 def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
76 goal.header.frame_id =
'map'
77 goal.header.stamp = time_stamp
79 row = randint(side_buffer, costmap.shape[0] - side_buffer)
80 col = randint(side_buffer, costmap.shape[1] - side_buffer)
82 start_x = start.pose.position.x
83 start_y = start.pose.position.y
86 x_diff = goal_x - start_x
87 y_diff = goal_y - start_y
88 dist = math.sqrt(x_diff ** 2 + y_diff ** 2)
90 if costmap[row, col] < max_cost
and dist > 3.0:
91 goal.pose.position.x = goal_x
92 goal.pose.position.y = goal_y
94 yaw = uniform(0, 1) * 2 * math.pi
95 quad = euler2quat(0.0, 0.0, yaw)
96 goal.pose.orientation.w = quad[0]
97 goal.pose.orientation.x = quad[1]
98 goal.pose.orientation.y = quad[2]
99 goal.pose.orientation.z = quad[3]
107 navigator = BasicNavigator()
110 print(
'Waiting for planner and smoother servers to activate')
111 navigator.waitUntilNav2Active(
'smoother_server',
'planner_server')
114 costmap_msg = navigator.getGlobalCostmap()
115 costmap = np.asarray(costmap_msg.data)
116 costmap.resize(costmap_msg.metadata.size_y, costmap_msg.metadata.size_x)
118 planner =
'SmacHybrid'
119 smoothers = [
'simple_smoother',
'constrained_smoother',
'sg_smoother']
122 time_stamp = navigator.get_clock().now().to_msg()
128 res = costmap_msg.metadata.resolution
129 while i < random_pairs:
130 print(
'Cycle: ', i,
'out of: ', random_pairs)
131 start = getRandomStart(costmap, max_cost, side_buffer, time_stamp, res)
132 goal = getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res)
133 print(
'Start', start)
135 result = getPlannerResults(navigator, start, goal, planner)
136 if result
is not None:
137 smoothed_results = getSmootherResults(navigator, result.path, smoothers)
138 if smoothed_results
is not None:
139 results.append(result)
140 results.append(smoothed_results)
143 print(
'Write Results...')
144 benchmark_dir = os.getcwd()
145 with open(os.path.join(benchmark_dir,
'results.pickle'),
'wb')
as f:
146 pickle.dump(results, f, pickle.HIGHEST_PROTOCOL)
148 with open(os.path.join(benchmark_dir,
'costmap.pickle'),
'wb')
as f:
149 pickle.dump(costmap_msg, f, pickle.HIGHEST_PROTOCOL)
151 smoothers.insert(0, planner)
152 with open(os.path.join(benchmark_dir,
'methods.pickle'),
'wb')
as f:
153 pickle.dump(smoothers, f, pickle.HIGHEST_PROTOCOL)
154 print(
'Write Complete')
159 if __name__ ==
'__main__':