16
16
from utils import *
17
17
18
18
P_prior = 0.5 # Prior occupancy probability
19
- P_occ = 0.9 # Probability that cell is occupied with total confidence
19
+ P_occ = 0.9 # Probability that cell is occupied with total confidence
20
20
P_free = 0.3 # Probability that cell is free with total confidence
21
21
22
- RESOLUTION = 0.025 # Grid resolution in [m]
22
+ RESOLUTION = 0.03 # Grid resolution in [m]
23
23
24
- MAP_NAME = 'stage_4 ' # map name without extension
24
+ MAP_NAME = 'world ' # map name without extension
25
25
26
26
if __name__ == '__main__' :
27
27
49
49
50
50
# Create grid map
51
51
gridMap = GridMap (X_lim = map_x_lim ,
52
- Y_lim = map_y_lim ,
53
- resolution = RESOLUTION ,
54
- p = P_prior )
52
+ Y_lim = map_y_lim ,
53
+ resolution = RESOLUTION ,
54
+ p = P_prior )
55
+
56
+ # Init time
57
+ t_start = perf_counter ()
58
+ sim_time = 0
59
+ step = 0
55
60
56
61
# Main loop
57
62
while not rospy .is_shutdown ():
109
114
set_pixel_color (bgr_image , x , y , 'GREEN' )
110
115
111
116
resized_image = cv2 .resize (src = bgr_image ,
112
- dsize = (500 , 500 ),
113
- interpolation = cv2 .INTER_AREA )
117
+ dsize = (500 , 500 ),
118
+ interpolation = cv2 .INTER_AREA )
114
119
115
120
rotated_image = cv2 .rotate (src = resized_image ,
116
- rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
121
+ rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
117
122
118
123
cv2 .imshow ("Grid map" , rotated_image )
119
124
cv2 .waitKey (1 )
120
125
126
+ # Calculate step time in [s]
127
+ t_step = perf_counter ()
128
+ step_time = t_step - t_start
129
+ sim_time += step_time
130
+ t_start = t_step
131
+ step += 1
132
+
133
+ print ('Step %d ==> %d [ms]' % (step , step_time * 1000 ))
134
+
121
135
rate .sleep ()
122
136
123
137
except rospy .ROSInterruptException :
124
138
125
139
print ('\r \n SIMULATION TERMINATED!' )
140
+ print ('\n Simulation time: %.2f [s]' % sim_time )
141
+ print ('Average step time: %d [ms]' % (sim_time * 1000 / step ))
142
+ print ('Frames per second: %.1f' % (step / sim_time ))
126
143
127
144
# Saving Grid Map
128
145
resized_image = cv2 .resize (src = gridMap .to_BGR_image (),
129
- dsize = (500 , 500 ),
130
- interpolation = cv2 .INTER_AREA )
146
+ dsize = (500 , 500 ),
147
+ interpolation = cv2 .INTER_AREA )
131
148
132
149
rotated_image = cv2 .rotate (src = resized_image ,
133
- rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
150
+ rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
134
151
135
152
flag_1 = cv2 .imwrite (img = rotated_image * 255.0 ,
136
- filename = MAPS_PATH + '/' + MAP_NAME + '_GRID_MAP .png' )
153
+ filename = MAPS_PATH + '/' + MAP_NAME + '_grid_map_TEST .png' )
137
154
138
155
# Calculating Maximum likelihood estimate of the map
139
156
gridMap .calc_MLE ()
140
157
141
158
# Saving MLE of the Grid Map
142
159
resized_image_MLE = cv2 .resize (src = gridMap .to_BGR_image (),
143
- dsize = (500 , 500 ),
144
- interpolation = cv2 .INTER_AREA )
160
+ dsize = (500 , 500 ),
161
+ interpolation = cv2 .INTER_AREA )
145
162
146
163
rotated_image_MLE = cv2 .rotate (src = resized_image_MLE ,
147
- rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
164
+ rotateCode = cv2 .ROTATE_90_COUNTERCLOCKWISE )
148
165
149
166
flag_2 = cv2 .imwrite (img = rotated_image_MLE * 255.0 ,
150
- filename = MAPS_PATH + '/' + MAP_NAME + '_GRID_MAP_MLE .png' )
167
+ filename = MAPS_PATH + '/' + MAP_NAME + '_grid_map_TEST_mle .png' )
151
168
152
169
if flag_1 and flag_2 :
153
170
print ('\n Grid map successfully saved!\n ' )
154
171
155
172
if cv2 .waitKey (0 ) == 27 :
156
173
cv2 .destroyAllWindows ()
157
174
158
- pass
175
+ pass
0 commit comments