forked from Daffan/the-barn-challenge
-
Notifications
You must be signed in to change notification settings - Fork 0
/
run.py
164 lines (127 loc) · 6.27 KB
/
run.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
import time
import argparse
import subprocess
import os
from os.path import join
import numpy as np
import rospy
import rospkg
from gazebo_simulation import GazeboSimulation
INIT_POSITION = [-2, 3, 1.57] # in world frame
GOAL_POSITION = [0, 10] # relative to the initial position
def compute_distance(p1, p2):
return ((p1[0] - p2[0]) ** 2 + (p1[1] - p2[1]) ** 2) ** 0.5
def path_coord_to_gazebo_coord(x, y):
RADIUS = 0.075
r_shift = -RADIUS - (30 * RADIUS * 2)
c_shift = RADIUS + 5
gazebo_x = x * (RADIUS * 2) + r_shift
gazebo_y = y * (RADIUS * 2) + c_shift
return (gazebo_x, gazebo_y)
if __name__ == "__main__":
parser = argparse.ArgumentParser(description = 'test BARN navigation challenge')
parser.add_argument('--world_idx', type=int, default=0)
parser.add_argument('--navigation_stack', type=str, default="launch/barn_nav.launch")
parser.add_argument('--gui', action="store_true")
parser.add_argument('--out', type=str, default="out.txt")
args = parser.parse_args()
##########################################################################################
## 0. Launch Gazebo Simulation
##########################################################################################
os.environ["JACKAL_LASER"] = "1"
os.environ["JACKAL_LASER_MODEL"] = "ust10"
os.environ["JACKAL_LASER_OFFSET"] = "-0.065 0 0.01"
world_name = "BARN/world_%d.world" %(args.world_idx)
print(">>>>>>>>>>>>>>>>>> Loading Gazebo Simulation with %s <<<<<<<<<<<<<<<<<<" %(world_name))
rospack = rospkg.RosPack()
base_path = rospack.get_path('jackal_helper')
launch_file = join(base_path, 'launch', 'gazebo_launch.launch')
world_name = join(base_path, "worlds", world_name)
gazebo_process = subprocess.Popen([
'roslaunch',
launch_file,
'world_name:=' + world_name,
'gui:=' + ("true" if args.gui else "false"),
])
time.sleep(5) # sleep to wait until the gazebo being created
rospy.init_node('gym', anonymous=True) #, log_level=rospy.FATAL)
rospy.set_param('/use_sim_time', True)
# GazeboSimulation provides useful interface to communicate with gazebo
gazebo_sim = GazeboSimulation(init_position=INIT_POSITION)
init_coor = (INIT_POSITION[0], INIT_POSITION[1])
goal_coor = (INIT_POSITION[0] + GOAL_POSITION[0], INIT_POSITION[1] + GOAL_POSITION[1])
pos = gazebo_sim.get_model_state().pose.position
curr_coor = (pos.x, pos.y)
collided = True
# check whether the robot is reset, the collision is False
while compute_distance(init_coor, curr_coor) > 0.1 or collided:
gazebo_sim.reset() # Reset to the initial position
pos = gazebo_sim.get_model_state().pose.position
curr_coor = (pos.x, pos.y)
collided = gazebo_sim.get_hard_collision()
time.sleep(1)
##########################################################################################
## 1. Launch your navigation stack
## (Customize this block to add your own navigation stack)
##########################################################################################
launch_file = join(base_path, 'launch/barn_nav.launch')
nav_stack_process = subprocess.Popen([
'roslaunch',
launch_file,
'goal_x:=0',
'goal_y:=10'
])
##########################################################################################
## 2. Start navigation
##########################################################################################
curr_time = rospy.get_time()
pos = gazebo_sim.get_model_state().pose.position
curr_coor = (pos.x, pos.y)
# check whether the robot started to move
while compute_distance(init_coor, curr_coor) < 0.1:
curr_time = rospy.get_time()
pos = gazebo_sim.get_model_state().pose.position
curr_coor = (pos.x, pos.y)
time.sleep(0.01)
# start navigation, check position, time and collision
start_time = curr_time
start_time_cpu = time.time()
collided = False
while compute_distance(goal_coor, curr_coor) > 1 and not collided and curr_time - start_time < 100:
curr_time = rospy.get_time()
pos = gazebo_sim.get_model_state().pose.position
curr_coor = (pos.x, pos.y)
print("World: %d, time: %.2f (s), x: %.2f (m), y: %.2f (m)" %(args.world_idx, curr_time - start_time, *curr_coor), end="\r")
collided = gazebo_sim.get_hard_collision()
while rospy.get_time() - curr_time < 0.1:
time.sleep(0.01)
##########################################################################################
## 3. Report metrics and generate log
##########################################################################################
print(">>>>>>>>>>>>>>>>>> Test finished! <<<<<<<<<<<<<<<<<<")
success = False
if collided:
status = "collided"
elif curr_time - start_time >= 100:
status = "timeout"
else:
status = "succeeded"
success = True
print("Navigation %s with time %.4f (s)" %(status, curr_time - start_time))
path_file_name = join(base_path, "worlds/BARN/path_files", "path_%d.npy" %args.world_idx)
path_array = np.load(path_file_name)
path_array = [path_coord_to_gazebo_coord(*p) for p in path_array]
path_array = np.insert(path_array, 0, (INIT_POSITION[0], INIT_POSITION[1]), axis=0)
path_array = np.insert(path_array, len(path_array), (INIT_POSITION[0] + GOAL_POSITION[0], INIT_POSITION[1] + GOAL_POSITION[1]), axis=0)
path_length = 0
for p1, p2 in zip(path_array[:-1], path_array[1:]):
path_length += compute_distance(p1, p2)
# Navigation metric: 1_success * optimal_time / clip(actual_time, 4 * optimal_time, 8 * optimal_time)
optimal_time = path_length / 2
actual_time = curr_time - start_time
nav_metric = int(success) * optimal_time / np.clip(actual_time, 4 * optimal_time, 8 * optimal_time)
print("Navigation metric: %.4f" %(nav_metric))
with open(args.out, "a") as f:
f.write("%d %d %d %d %.4f %.4f\n" %(args.world_idx, success, collided, (curr_time - start_time)>=100, curr_time - start_time, nav_metric))
gazebo_process.terminate()
nav_stack_process.terminate()