17 from geometry_msgs.msg
import PoseStamped
26 from random
import seed
27 from random
import randint
28 from random
import uniform
30 from transforms3d.euler
import euler2quat
35 def getPlannerResults(navigator, initial_pose, goal_pose, planner):
36 return navigator._getPathImpl(initial_pose, goal_pose, planner, use_start=
True)
38 def getSmootherResults(navigator, path, smoothers):
40 for smoother
in smoothers:
41 smoothed_result = navigator._smoothPathImpl(path, smoother)
42 if smoothed_result
is not None:
43 smoothed_results.append(smoothed_result)
45 print(smoother,
" failed to smooth the path")
47 return smoothed_results
49 def getRandomStart(costmap, max_cost, side_buffer, time_stamp, res):
51 start.header.frame_id =
'map'
52 start.header.stamp = time_stamp
54 row = randint(side_buffer, costmap.shape[0]-side_buffer)
55 col = randint(side_buffer, costmap.shape[1]-side_buffer)
57 if costmap[row, col] < max_cost:
58 start.pose.position.x = col*res
59 start.pose.position.y = row*res
61 yaw = uniform(0, 1) * 2*math.pi
62 quad = euler2quat(0.0, 0.0, yaw)
63 start.pose.orientation.w = quad[0]
64 start.pose.orientation.x = quad[1]
65 start.pose.orientation.y = quad[2]
66 start.pose.orientation.z = quad[3]
70 def getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res):
72 goal.header.frame_id =
'map'
73 goal.header.stamp = time_stamp
75 row = randint(side_buffer, costmap.shape[0]-side_buffer)
76 col = randint(side_buffer, costmap.shape[1]-side_buffer)
78 start_x = start.pose.position.x
79 start_y = start.pose.position.y
82 x_diff = goal_x - start_x
83 y_diff = goal_y - start_y
84 dist = math.sqrt(x_diff ** 2 + y_diff ** 2)
86 if costmap[row, col] < max_cost
and dist > 3.0:
87 goal.pose.position.x = goal_x
88 goal.pose.position.y = goal_y
90 yaw = uniform(0, 1) * 2*math.pi
91 quad = euler2quat(0.0, 0.0, yaw)
92 goal.pose.orientation.w = quad[0]
93 goal.pose.orientation.x = quad[1]
94 goal.pose.orientation.y = quad[2]
95 goal.pose.orientation.z = quad[3]
102 navigator = BasicNavigator()
105 print(
"Waiting for planner and smoother servers to activate")
106 navigator.waitUntilNav2Active(
'smoother_server',
'planner_server')
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)
113 planner =
'SmacHybrid'
114 smoothers = [
'simple_smoother',
'constrained_smoother']
117 time_stamp = navigator.get_clock().now().to_msg()
123 res = costmap_msg.metadata.resolution
124 while i < random_pairs:
125 print(
"Cycle: ", i,
"out of: ", random_pairs)
126 start = getRandomStart(costmap, max_cost, side_buffer, time_stamp, res)
127 goal = getRandomGoal(costmap, start, max_cost, side_buffer, time_stamp, res)
128 print(
"Start", start)
130 result = getPlannerResults(navigator, start, goal, planner)
131 if result
is not None:
132 smoothed_results = getSmootherResults(navigator, result.path, smoothers)
133 if smoothed_results
is not None:
134 results.append(result)
135 results.append(smoothed_results)
138 print(planner,
" planner failed to produce the path")
140 print(
"Write Results...")
141 benchmark_dir = os.getcwd()
142 with open(os.path.join(benchmark_dir,
'results.pickle'),
'wb')
as f:
143 pickle.dump(results, f, pickle.HIGHEST_PROTOCOL)
145 with open(os.path.join(benchmark_dir,
'costmap.pickle'),
'wb')
as f:
146 pickle.dump(costmap_msg, f, pickle.HIGHEST_PROTOCOL)
148 smoothers.insert(0, planner)
149 with open(os.path.join(benchmark_dir,
'methods.pickle'),
'wb')
as f:
150 pickle.dump(smoothers, f, pickle.HIGHEST_PROTOCOL)
151 print(
"Write Complete")
156 if __name__ ==
'__main__':