-
Notifications
You must be signed in to change notification settings - Fork 0
/
demo_in_ros.py
266 lines (216 loc) · 9.01 KB
/
demo_in_ros.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
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
import argparse
import glob
from pathlib import Path
import time
import os
import sys
import math
import threading
import rospy
from std_msgs.msg import Header
from sensor_msgs.msg import Image
from sensor_msgs.msg import PointCloud2
from visualization_msgs.msg import Marker, MarkerArray
import matplotlib.pyplot as plt
try:
import cv2
except ImportError:
import sys
sys.path.remove('/opt/ros/kinetic/lib/python2.7/dist-packages')
import cv2
import numpy as np
import torch
from data import cfg, cfg_from_yaml_file
from data import KittiDataset
from second_net import build_network, load_data_to_gpu
from utils import common_utils, calibration_kitti
from utils import opencv_vis_utils
from utils import numpy_pc2
image_lock = threading.Lock()
lidar_lock = threading.Lock()
def parse_config():
parser = argparse.ArgumentParser(description='arg parser')
parser.add_argument('--cfg_file', type=str, default='data/config.yaml',
help='specify the config file')
parser.add_argument('--ckpt', type=str, default=None,
help='specify the pretrained model')
parser.add_argument('--display', action='store_true', default=False,
help='whether to display results onto the RGB image')
parser.add_argument('--print', action='store_true', default=False,
help='whether to print results in the txt file')
parser.add_argument('--score_thresh', type=float, default=0.1,
help='specify the score threshold')
parser.add_argument('--sub_image', type=str, default='/kitti/camera_color_left/image_raw',
help='the image topic to subscribe')
parser.add_argument('--sub_lidar', type=str, default='/kitti/velo/pointcloud',
help='the lidar topic to subscribe')
parser.add_argument('--pub_marker', type=str, default='/result',
help='the marker topic to publish')
parser.add_argument('--frame_rate', type=int, default=10,
help='working frequency')
parser.add_argument('--frame_id', type=str, default=None,
help='frame id for ROS msg (same as lidar topic by default)')
parser.add_argument('--calib_file', type=str, default='data/kitti/testing/calib/000000.txt',
help='specify the calibration file')
args = parser.parse_args()
cfg_from_yaml_file(args.cfg_file, cfg)
if args.score_thresh:
cfg.MODEL.POST_PROCESSING.SCORE_THRESH = args.score_thresh
return args, cfg
def publish_marker_msg(pub, boxes, labels, frame_id, frame_rate, color_map):
markerarray = MarkerArray()
for i in range(boxes.shape[0]):
marker = Marker()
marker.header = Header()
marker.header.frame_id = frame_id
marker.header.stamp = rospy.Time.now()
marker.ns = labels[i]
marker.id = i
marker.type = Marker.CUBE
marker.action = Marker.ADD
marker.pose.position.x = boxes[i][0]
marker.pose.position.y = boxes[i][1]
marker.pose.position.z = boxes[i][2]
marker.pose.orientation.x = 0.0
marker.pose.orientation.y = 0.0
marker.pose.orientation.z = math.sin(0.5 * boxes[i][6])
marker.pose.orientation.w = math.cos(0.5 * boxes[i][6])
marker.scale.x = boxes[i][3]
marker.scale.y = boxes[i][4]
marker.scale.z = boxes[i][5]
marker.color.r = color_map[labels[i]][2] / 255.0
marker.color.g = color_map[labels[i]][1] / 255.0
marker.color.b = color_map[labels[i]][0] / 255.0
marker.color.a = 0.75 # 0 for invisible
marker.lifetime = rospy.Duration(1 / frame_rate)
markerarray.markers.append(marker)
pub.publish(markerarray)
def display(img, v_writer, win_name='result'):
cv2.namedWindow(win_name, cv2.WINDOW_NORMAL)
cv2.imshow(win_name, img)
v_writer.write(img)
key = cv2.waitKey(1)
if key == 27:
v_writer.release()
return False
else:
return True
def print_info(frame, stamp, delay, labels, scores, boxes, file_name='result.txt'):
time_str = 'frame:%d stamp:%.3f delay:%.3f' % (frame, stamp, delay)
print(time_str)
with open(file_name, 'a') as fob:
fob.write(time_str + '\n')
for i in range(len(labels)):
box = boxes[i]
info_str = 'box:%.2f %.2f %.2f %.2f %.2f %.2f %.2f score:%.2f label:%s' % (
box[0], box[1], box[2], box[3], box[4], box[5], box[6], scores[i], labels[i]
)
print(info_str)
with open(file_name, 'a') as fob:
fob.write(info_str + '\n')
print()
with open(file_name, 'a') as fob:
fob.write('\n')
def image_callback(image):
global image_header, image_frame
image_lock.acquire()
if image_header is None:
image_header = image.header
image_frame = np.frombuffer(image.data, dtype=np.uint8).reshape(image.height, image.width, -1)
image_lock.release()
def lidar_callback(lidar):
global lidar_header, lidar_frame
lidar_lock.acquire()
if lidar_header is None:
lidar_header = lidar.header
lidar_frame = numpy_pc2.pointcloud2_to_xyzi_array(lidar, remove_nans=True)
lidar_lock.release()
def timer_callback(event):
global image_frame
image_lock.acquire()
cur_image = image_frame.copy()
image_lock.release()
global lidar_frame
lidar_lock.acquire()
cur_lidar = lidar_frame.copy()
lidar_lock.release()
global frame
frame += 1
start = time.time()
d = demo_dataset
frame_id = args.frame_id
image_shape = np.array(cur_image.shape[:2], dtype=np.int32)
if d.dataset_cfg.FOV_POINTS_ONLY:
points = cur_lidar[d.get_fov_flag(cur_lidar, image_shape, calib)]
else:
points = cur_lidar
data_dict = {
'frame_id': frame_id,
'points': points, # (N, 4)
'calib': calib,
'image_shape': image_shape,
}
data_dict = d.prepare_data(data_dict=data_dict)
data_dict = d.collate_batch([data_dict])
with torch.no_grad():
load_data_to_gpu(data_dict)
pred_dicts, _ = model.forward(data_dict)
ref_boxes = pred_dicts[0]['pred_boxes'].cpu().numpy()
ref_labels = [cfg.CLASS_NAMES[j - 1] for j in pred_dicts[0]['pred_labels']]
ref_scores = pred_dicts[0]['pred_scores'].cpu().numpy()
publish_marker_msg(pub_marker, ref_boxes, ref_labels,
frame_id=args.frame_id, frame_rate=args.frame_rate,
color_map=opencv_vis_utils.box_colormap
)
if args.display:
if ref_boxes is not None:
cur_image = opencv_vis_utils.draw_box(cur_image, calib, ref_boxes, ref_labels)
if not display(cur_image, v_writer, win_name='result'):
print("\nReceived the shutdown signal.\n")
rospy.signal_shutdown("Everything is over now.")
if args.print:
cur_stamp = rospy.Time.now()
cur_stamp = cur_stamp.secs + 0.000000001 * cur_stamp.nsecs
delay = round(time.time() - start, 3)
print_info(frame, cur_stamp, delay, ref_labels, ref_scores, ref_boxes, result_file)
if __name__ == '__main__':
args, cfg = parse_config()
logger = common_utils.create_logger()
logger.info('-----------------Quick Demo of SECOND in ROS-------------------------')
rospy.init_node("second", anonymous=True, disable_signals=True)
frame = 0
demo_dataset = KittiDataset(
dataset_cfg=cfg.DATA_CONFIG, class_names=cfg.CLASS_NAMES, training=False, logger=logger,
)
model = build_network(model_cfg=cfg.MODEL, num_class=len(cfg.CLASS_NAMES), dataset=demo_dataset)
model.load_params_from_file(filename=args.ckpt, logger=logger, to_cpu=True)
model.cuda()
model.eval()
calib_file = Path(args.calib_file)
assert calib_file.exists(), 'Calibration file not found: %s' % calib_file
calib = calibration_kitti.Calibration(calib_file)
image_header, image_frame = None, None
lidar_header, lidar_frame = None, None
rospy.Subscriber(args.sub_image, Image, image_callback, queue_size=1,
buff_size=52428800)
rospy.Subscriber(args.sub_lidar, PointCloud2, lidar_callback, queue_size=1,
buff_size=52428800)
while image_frame is None or lidar_frame is None:
time.sleep(0.1)
print('Waiting for topic %s and %s...' % (args.sub_image, args.sub_lidar))
print(' Done.\n')
if args.frame_id is None:
args.frame_id = lidar_header.frame_id
if args.display:
win_h, win_w = image_frame.shape[0], image_frame.shape[1]
v_path = 'result.mp4'
v_format = cv2.VideoWriter_fourcc(*"mp4v")
v_writer = cv2.VideoWriter(v_path, v_format, args.frame_rate, (win_w, win_h), True)
if args.print:
result_file = 'result.txt'
with open(result_file, 'w') as fob:
fob.seek(0)
fob.truncate()
pub_marker = rospy.Publisher(args.pub_marker, MarkerArray, queue_size=1)
rospy.Timer(rospy.Duration(1 / args.frame_rate), timer_callback)
rospy.spin()