-
Notifications
You must be signed in to change notification settings - Fork 267
/
Copy pathpushbroom-stereo-main.cpp
1254 lines (943 loc) · 42.5 KB
/
pushbroom-stereo-main.cpp
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
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/**
* Program that runs pushbroom stereo.
* This grabs stereo pairs from Point Grey
* Firefly MV USB cameras, perfroms the single-disparity
* stereo algorithm on them, and publishes the results
* to LCM.
*
* Copyright 2013-2015, Andrew Barry <[email protected]>
*
*/
#include "pushbroom-stereo-main.hpp"
bool show_display; // set to true to show opencv images on screen
int show_display_wait = 1; // milli seconds to wait between frames when showing display
bool disable_stereo = false;
bool show_unrectified = false;
bool display_hud = false;
bool record_hud = false;
bool visualize_stereo_hits = true;
bool publish_all_images = false;
lcmt_stereo *stereo_lcm_msg = NULL; // for use in visualizing stereo hits recorded on the fly
int force_brightness = -1;
int force_exposure = -1;
int inf_sad_add = 0;
int y_offset = 0;
int file_frame_skip = 0;
int current_video_number = -1;
RecordingManager recording_manager;
// global for where we are drawing a line on the image
int lineLeftImgPosition = -1;
int lineLeftImgPositionY = -1;
// lcm subscription to the control channel
lcmt_stereo_control_subscription_t *stereo_control_sub;
PushbroomStereoState state; // HACK
// subscriptions to data
lcmt_stereo_subscription_t *stereo_replay_sub;
lcmt_cpu_info_subscription_t *cpu_info_sub1;
lcmt_cpu_info_subscription_t *cpu_info_sub2;
lcmt_cpu_info_subscription_t *cpu_info_sub3;
lcmt_log_size_subscription_t *log_size_sub1;
lcmt_log_size_subscription_t *log_size_sub2;
lcmt_log_size_subscription_t *log_size_sub3;
mav_pose_t_subscription_t *mav_pose_t_sub;
lcmt_baro_airspeed_subscription_t *baro_airspeed_sub;
lcmt_battery_status_subscription_t *battery_status_sub;
lcmt_deltawing_u_subscription_t *servo_out_sub;
mav_gps_data_t_subscription_t *mav_gps_data_t_sub;
int numFrames = 0;
bool quiet_mode = false;
double timer_sum = 0;
int timer_count = 0;
dc1394_t *d;
dc1394camera_t *camera;
dc1394_t *d2;
dc1394camera_t *camera2;
OpenCvStereoConfig stereoConfig;
/**
* Cleanly handles and exit from a command-line
* ctrl-c signal.
*
* @param s
*
*/
void control_c_handler(int s)
{
cout << endl << "exiting via ctrl-c" << endl;
if (recording_manager.UsingLiveCameras()) {
StopCapture(d, camera);
StopCapture(d2, camera2);
cout << "\tpress ctrl+\\ to quit while writing video." << endl;
recording_manager.FlushBufferToDisk();
}
exit(0);
}
/**
* Handles LCM control messages. Is called when an LCM message is received on the channel.
*/
void lcm_stereo_control_handler(const lcm_recv_buf_t *rbuf, const char* channel, const lcmt_stereo_control *msg, void *user)
{
/*
* The way this works is that as soon as
* the program starts, stereo is always running.
*
* stereo control:
* 0: write to disk and then restart
* 1: (re)start record
* 2: pause
*
*/
// got a control message, so parse it and figure out what we should do
if (msg->stereo_control == 0)
{
// write video, then start recording again
recording_manager.FlushBufferToDisk();
recording_manager.BeginNewRecording();
} else if (msg->stereo_control == 1)
{
// record
cout << endl << "(Re)starting recording." << endl;
recording_manager.BeginNewRecording();
} else if (msg->stereo_control == 2)
{
// pause recording if we were recording
cout << "Recording paused." << endl;
recording_manager.SetRecordingOn(false);
} else {
// got an unknown command
fprintf(stderr, "WARNING: Unknown stereo_control command: %d", int(msg->stereo_control));
}
}
int main(int argc, char *argv[])
{
// get input arguments
string configFile = "";
string video_file_left = "", video_file_right = "", video_directory = "";
int starting_frame_number = 0;
bool enable_gamma = false;
float random_results = -1.0;
int last_frame_number = -1;
int last_playback_frame_number = -2;
ConciseArgs parser(argc, argv);
parser.add(configFile, "c", "config", "Configuration file containing camera GUIDs, etc.", true);
parser.add(show_display, "d", "show-dispaly", "Enable for visual debugging display. Will reduce framerate significantly.");
parser.add(show_display_wait, "w", "show-display-wait", "Optional argument to decrease framerate for lower network traffic when forwarding the display.");
parser.add(show_unrectified, "u", "show-unrectified", "When displaying images, do not apply rectification.");
parser.add(disable_stereo, "s", "disable-stereo", "Disable online stereo processing.");
parser.add(force_brightness, "b", "force-brightness", "Force a brightness setting.");
parser.add(force_exposure, "e", "force-exposure", "Force an exposure setting.");
parser.add(quiet_mode, "q", "quiet", "Reduce text output.");
parser.add(video_file_left, "l", "video-file-left", "Do not use cameras, instead use this video file (also requires a right video file).");
parser.add(video_file_right, "t", "video-file-right", "Right video file, only for use with the -l option.");
parser.add(video_directory, "i", "video-directory", "Directory to search for videos in (for playback).");
parser.add(starting_frame_number, "f", "starting-frame", "Frame to start at when playing back videos.");
parser.add(display_hud, "v", "hud", "Overlay HUD on display images.");
parser.add(record_hud, "x", "record-hud", "Record the HUD display.");
parser.add(file_frame_skip, "p", "skip", "Number of frames skipped in recording (for playback).");
parser.add(enable_gamma, "g", "enable-gamma", "Turn gamma on for both cameras.");
parser.add(random_results, "R", "random-results", "Number of random points to produce per frame. Can be a float in which case we'll take a random sample to decide if to produce the last one. Disables real stereo processing. Only for debugging / analysis!");
parser.add(publish_all_images, "P", "publish-all-images", "Publish all images to LCM");
parser.parse();
// parse the config file
if (ParseConfigFile(configFile, &stereoConfig) != true)
{
fprintf(stderr, "Failed to parse configuration file, quitting.\n");
return -1;
}
if (video_file_left.length() > 0
&& video_file_right.length() <= 0) {
fprintf(stderr, "Error: for playback you must specify both "
"a right and left video file. (Only got a left one.)\n");
return -1;
}
if (video_file_left.length() <= 0
&& video_file_right.length() > 0) {
fprintf(stderr, "Error: for playback you must specify both "
"a right and left video file. (Only got a right one.)\n");
return -1;
}
recording_manager.Init(stereoConfig);
// attempt to load video files / directories
if (video_file_left.length() > 0) {
if (recording_manager.LoadVideoFiles(video_file_left, video_file_right) != true) {
// don't have videos, bail out.
return -1;
}
}
if (video_directory.length() > 0) {
if (recording_manager.SetPlaybackVideoDirectory(video_directory) != true) {
// bail
return -1;
}
}
recording_manager.SetQuietMode(quiet_mode);
recording_manager.SetPlaybackFrameNumber(starting_frame_number);
uint64 guid = stereoConfig.guidLeft;
uint64 guid2 = stereoConfig.guidRight;
// start up LCM
lcm_t * lcm;
lcm = lcm_create (stereoConfig.lcmUrl.c_str());
unsigned long elapsed;
Hud hud;
// --- setup control-c handling ---
struct sigaction sigIntHandler;
sigIntHandler.sa_handler = control_c_handler;
sigemptyset(&sigIntHandler.sa_mask);
sigIntHandler.sa_flags = 0;
sigaction(SIGINT, &sigIntHandler, NULL);
// --- end ctrl-c handling code ---
dc1394error_t err;
dc1394error_t err2;
// tell opencv to use only one core so that we can manage our
// own threading without a fight
setNumThreads(1);
if (recording_manager.UsingLiveCameras()) {
d = dc1394_new ();
if (!d)
cerr << "Could not create dc1394 context" << endl;
d2 = dc1394_new ();
if (!d2)
cerr << "Could not create dc1394 context for camera 2" << endl;
camera = dc1394_camera_new (d, guid);
if (!camera)
{
cerr << "Could not create dc1394 camera... quitting." << endl;
exit(1);
}
camera2 = dc1394_camera_new (d2, guid2);
if (!camera2)
cerr << "Could not create dc1394 camera for camera 2" << endl;
// reset the bus
dc1394_reset_bus(camera);
dc1394_reset_bus(camera2);
// setup
err = setup_gray_capture(camera, DC1394_VIDEO_MODE_FORMAT7_1);
DC1394_ERR_CLN_RTN(err, cleanup_and_exit(camera), "Could not setup camera");
err2 = setup_gray_capture(camera2, DC1394_VIDEO_MODE_FORMAT7_1);
DC1394_ERR_CLN_RTN(err2, cleanup_and_exit(camera2), "Could not setup camera number 2");
// enable camera
err = dc1394_video_set_transmission(camera, DC1394_ON);
DC1394_ERR_CLN_RTN(err, cleanup_and_exit(camera), "Could not start camera iso transmission");
err2 = dc1394_video_set_transmission(camera2, DC1394_ON);
DC1394_ERR_CLN_RTN(err2, cleanup_and_exit(camera2), "Could not start camera iso transmission for camera number 2");
InitBrightnessSettings(camera, camera2, enable_gamma);
}
if (show_display) {
namedWindow("Input", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Input2", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Stereo", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Left Block", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Right Block", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Debug 1", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
namedWindow("Debug 2", CV_WINDOW_AUTOSIZE | CV_WINDOW_KEEPRATIO);
setMouseCallback("Input", onMouse); // for drawing disparity lines
setMouseCallback("Stereo", onMouseStereo, &hud); // for drawing disparity lines
moveWindow("Input", stereoConfig.displayOffsetX + 100, stereoConfig.displayOffsetY + 100);
moveWindow("Stereo", stereoConfig.displayOffsetX + 100, stereoConfig.displayOffsetY + 370);
moveWindow("Input2", stereoConfig.displayOffsetX + 478, stereoConfig.displayOffsetY + 100);
moveWindow("Left Block", stereoConfig.displayOffsetX + 900, stereoConfig.displayOffsetY + 100);
moveWindow("Right Block", stereoConfig.displayOffsetX + 1400, stereoConfig.displayOffsetY + 100);
moveWindow("Debug 1", stereoConfig.displayOffsetX + 900, stereoConfig.displayOffsetY + 670);
moveWindow("Debug 2", stereoConfig.displayOffsetX + 1400, stereoConfig.displayOffsetY + 670);
} // show display
if (show_display || publish_all_images) {
// if a channel exists, subscribe to it
if (stereoConfig.stereo_replay_channel.length() > 0) {
stereo_replay_sub = lcmt_stereo_subscribe(lcm, stereoConfig.stereo_replay_channel.c_str(), &stereo_replay_handler, &hud);
}
if (stereoConfig.pose_channel.length() > 0) {
mav_pose_t_sub = mav_pose_t_subscribe(lcm, stereoConfig.pose_channel.c_str(), &mav_pose_t_handler, &hud);
}
if (stereoConfig.gps_channel.length() > 0) {
mav_gps_data_t_sub = mav_gps_data_t_subscribe(lcm, stereoConfig.gps_channel.c_str(), &mav_gps_data_t_handler, &hud);
}
if (stereoConfig.baro_airspeed_channel.length() > 0) {
baro_airspeed_sub = lcmt_baro_airspeed_subscribe(lcm, stereoConfig.baro_airspeed_channel.c_str(), &baro_airspeed_handler, &hud);
}
if (stereoConfig.servo_out_channel.length() > 0) {
servo_out_sub = lcmt_deltawing_u_subscribe(lcm, stereoConfig.servo_out_channel.c_str(), &servo_out_handler, &hud);
}
if (stereoConfig.battery_status_channel.length() > 0) {
battery_status_sub = lcmt_battery_status_subscribe(lcm, stereoConfig.battery_status_channel.c_str(), &battery_status_handler, &hud);
}
if (stereoConfig.cpu_info_channel1.length() > 0) {
cpu_info_sub1 = lcmt_cpu_info_subscribe(lcm, stereoConfig.cpu_info_channel1.c_str(), &cpu_info_handler, &recording_manager);
cpu_info_sub2 = lcmt_cpu_info_subscribe(lcm, stereoConfig.cpu_info_channel2.c_str(), &cpu_info_handler, &recording_manager);
cpu_info_sub3 = lcmt_cpu_info_subscribe(lcm, stereoConfig.cpu_info_channel3.c_str(), &cpu_info_handler, &recording_manager);
}
if (stereoConfig.log_size_channel1.length() > 0) {
log_size_sub1 = lcmt_log_size_subscribe(lcm, stereoConfig.log_size_channel1.c_str(), &log_size_handler, &hud);
log_size_sub2 = lcmt_log_size_subscribe(lcm, stereoConfig.log_size_channel2.c_str(), &log_size_handler, &hud);
log_size_sub3 = lcmt_log_size_subscribe(lcm, stereoConfig.log_size_channel3.c_str(), &log_size_handler, &hud);
}
} // end show_display || publish_all_images
// load calibration
OpenCvStereoCalibration stereoCalibration;
if (LoadCalibration(stereoConfig.calibrationDir, &stereoCalibration) != true)
{
cerr << "Error: failed to read calibration files. Quitting." << endl;
return -1;
}
int inf_disparity_tester, disparity_tester;
disparity_tester = GetDisparityForDistance(10, stereoCalibration, &inf_disparity_tester);
std::cout << "computed disparity is = " << disparity_tester << ", inf disparity = " << inf_disparity_tester << std::endl;
// subscribe to the stereo control channel
stereo_control_sub = lcmt_stereo_control_subscribe(lcm, stereoConfig.stereoControlChannel.c_str(), &lcm_stereo_control_handler, NULL);
Mat imgDisp;
Mat imgDisp2;
// initilize default parameters
//PushbroomStereoState state; // HACK
state.disparity = stereoConfig.disparity;
state.zero_dist_disparity = stereoConfig.infiniteDisparity;
state.sobelLimit = stereoConfig.interestOperatorLimit;
state.horizontalInvarianceMultiplier = stereoConfig.horizontalInvarianceMultiplier;
state.blockSize = stereoConfig.blockSize;
state.random_results = random_results;
state.check_horizontal_invariance = true;
if (state.blockSize > 10 || state.blockSize < 1)
{
fprintf(stderr, "Warning: block size is very large "
"or small (%d). Expect trouble.\n", state.blockSize);
}
state.sadThreshold = stereoConfig.sadThreshold;
state.mapxL = stereoCalibration.mx1fp;
state.mapxR = stereoCalibration.mx2fp;
state.Q = stereoCalibration.qMat;
state.show_display = show_display;
state.lastValidPixelRow = stereoConfig.lastValidPixelRow;
Mat matL, matR;
bool quit = false;
if (recording_manager.UsingLiveCameras()) {
matL = GetFrameFormat7(camera);
matR = GetFrameFormat7(camera2);
if (recording_manager.InitRecording(matL, matR) != true) {
// failed to init recording, things are going bad. bail.
return -1;
}
// before we start, turn the cameras on and set the brightness and exposure
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
// grab a few frames and send them over LCM for the user
// to verify that everything is working
if (!show_display && !publish_all_images) {
printf("Sending init images over LCM... ");
fflush(stdout);
for (int i = 0; i < 5; i++) {
matL = GetFrameFormat7(camera);
SendImageOverLcm(lcm, "stereo_image_left", matL, 50);
matR = GetFrameFormat7(camera2);
SendImageOverLcm(lcm, "stereo_image_right", matR, 50);
// don't send these too fast, otherwise we'll flood the ethernet link
// and not actually be helpful
// wait one second
printf(".");
fflush(stdout);
sleep(1);
}
printf(" done.\n");
}
} // recording_manager.UsingLiveCameras()
// spool up worker threads
PushbroomStereo pushbroom_stereo;
// start the framerate clock
struct timeval start, now;
gettimeofday( &start, NULL );
while (quit == false) {
// get the frames from the camera
if (recording_manager.UsingLiveCameras()) {
// we would like to match brightness every frame
// but that would really hurt our framerate
// match brightness every 10 frames instead
if (numFrames % MATCH_BRIGHTNESS_EVERY_N_FRAMES == 0)
{
MatchBrightnessSettings(camera, camera2);
}
// capture images from the cameras
matL = GetFrameFormat7(camera);
matR = GetFrameFormat7(camera2);
// record video
recording_manager.AddFrames(matL, matR);
} else {
// using a video file -- get the next frame
recording_manager.GetFrames(matL, matR);
}
cv::vector<Point3f> pointVector3d;
cv::vector<uchar> pointColors;
cv::vector<Point3i> pointVector2d; // for display
cv::vector<Point3i> pointVector2d_inf; // for display
// do the main stereo processing
if (disable_stereo != true) {
gettimeofday( &now, NULL );
double before = now.tv_usec + now.tv_sec * 1000 * 1000;
pushbroom_stereo.ProcessImages(matL, matR, &pointVector3d, &pointColors, &pointVector2d, state);
gettimeofday( &now, NULL );
double after = now.tv_usec + now.tv_sec * 1000 * 1000;
timer_sum += after-before;
timer_count ++;
}
// build an LCM message for the stereo data
lcmt_stereo msg;
if (recording_manager.UsingLiveCameras() || stereo_lcm_msg == NULL) {
msg.timestamp = getTimestampNow();
} else {
// if we are replaying videos, preserve the timestamp of the original video
msg.timestamp = stereo_lcm_msg->timestamp;
}
msg.number_of_points = (int)pointVector3d.size();
float x[msg.number_of_points];
float y[msg.number_of_points];
float z[msg.number_of_points];
uchar grey[msg.number_of_points];
for (unsigned int i=0;i<pointVector3d.size();i++) {
x[i] = pointVector3d[i].x / stereoConfig.calibrationUnitConversion;
y[i] = pointVector3d[i].y / stereoConfig.calibrationUnitConversion;
z[i] = pointVector3d[i].z / stereoConfig.calibrationUnitConversion;
grey[i] = pointColors[i];
}
msg.x = x;
msg.y = y;
msg.z = z;
msg.grey = grey;
msg.frame_number = recording_manager.GetFrameNumber();
if (recording_manager.UsingLiveCameras()) {
msg.frame_number = msg.frame_number - 1; // minus one since recording manager has
// already recorded this frame (above in
// AddFrames) but we haven't made a message
// for it yet
}
msg.video_number = recording_manager.GetRecVideoNumber();
// publish the LCM message
if (last_frame_number != msg.frame_number) {
lcmt_stereo_publish(lcm, "stereo", &msg);
last_frame_number = msg.frame_number;
}
if (publish_all_images) {
if (recording_manager.GetFrameNumber() != last_playback_frame_number) {
SendImageOverLcm(lcm, "stereo_image_left", matL, 80);
SendImageOverLcm(lcm, "stereo_image_right", matR, 80);
last_playback_frame_number = recording_manager.GetFrameNumber();
}
//process LCM until there are no more messages
// this allows us to drop frames if we are behind
while (NonBlockingLcm(lcm)) {}
}
Mat matDisp, remapL, remapR;
if (show_display) {
// we remap again here because we're just in display
Mat remapLtemp(matL.rows, matL.cols, matL.depth());
Mat remapRtemp(matR.rows, matR.cols, matR.depth());
remapL = remapLtemp;
remapR = remapRtemp;
remap(matL, remapL, stereoCalibration.mx1fp, Mat(), INTER_NEAREST);
remap(matR, remapR, stereoCalibration.mx2fp, Mat(), INTER_NEAREST);
remapL.copyTo(matDisp);
//process LCM until there are no more messages
// this allows us to drop frames if we are behind
while (NonBlockingLcm(lcm)) {}
} // end show_display
if (show_display) {
for (unsigned int i=0;i<pointVector2d.size();i++) {
int x2 = pointVector2d[i].x;
int y2 = pointVector2d[i].y;
//int sad = pointVector2d[i].z;
rectangle(matDisp, Point(x2,y2), Point(x2+state.blockSize, y2+state.blockSize), 0, CV_FILLED);
rectangle(matDisp, Point(x2+1,y2+1), Point(x2+state.blockSize-1, y2-1+state.blockSize), 255);
}
// draw pixel blocks
if (lineLeftImgPosition >= 0 && lineLeftImgPositionY > 1) {
DisplayPixelBlocks(remapL, remapR, lineLeftImgPosition - state.blockSize/2, lineLeftImgPositionY - state.blockSize/2, state, &pushbroom_stereo);
}
// draw a line for the user to show disparity
DrawLines(remapL, remapR, matDisp, lineLeftImgPosition, lineLeftImgPositionY, state.disparity, state.zero_dist_disparity);
if (visualize_stereo_hits == true && stereo_lcm_msg != NULL) {
// transform the points from 3D space back onto the image's 2D space
vector<Point3f> lcm_points;
Get3DPointsFromStereoMsg(stereo_lcm_msg, &lcm_points);
// draw the points on the unrectified image (to see these
// you must pass the -u flag)
Draw3DPointsOnImage(matL, &lcm_points, stereoCalibration.M1, stereoCalibration.D1, stereoCalibration.R1, 128);
}
if (show_unrectified == false) {
imshow("Input", remapL);
imshow("Input2", remapR);
} else {
imshow("Input", matL);
imshow("Input2", matR);
}
if (display_hud) {
Mat with_hud;
recording_manager.SetHudNumbers(&hud);
hud.DrawHud(matDisp, with_hud);
if (record_hud) {
// put this frame into the HUD recording
recording_manager.RecFrameHud(with_hud);
}
imshow("Stereo", with_hud);
} else {
imshow("Stereo", matDisp);
}
char key = waitKey(show_display_wait);
if (key != 255 && key != -1)
{
cout << endl << key << endl;
}
switch (key)
{
case 'T':
state.disparity --;
break;
case 'R':
state.disparity ++;
break;
case 'w':
state.sobelLimit += 10;
break;
case 's':
state.sobelLimit -= 10;
break;
case 'd':
state.horizontalInvarianceMultiplier -= 0.1;
break;
case 'D':
state.horizontalInvarianceMultiplier += 0.1;
break;
case 'g':
state.blockSize ++;
break;
case 'b':
state.blockSize --;
if (state.blockSize < 1) {
state.blockSize = 1;
}
break;
case 'Y':
state.sadThreshold += 50;
break;
case 'y':
state.sadThreshold ++;
break;
case 'h':
state.sadThreshold --;
break;
case 'H':
state.sadThreshold -= 50;
break;
case 'm':
if (recording_manager.UsingLiveCameras()) {
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
}
break;
case '1':
force_brightness --;
if (recording_manager.UsingLiveCameras()) {
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
}
break;
case '2':
force_brightness ++;
if (recording_manager.UsingLiveCameras()) {
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
}
break;
case '3':
force_exposure --;
if (recording_manager.UsingLiveCameras()) {
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
}
break;
case '4':
force_exposure ++;
if (recording_manager.UsingLiveCameras()) {
MatchBrightnessSettings(camera, camera2, true, force_brightness, force_exposure);
}
break;
case '5':
// to show SAD boxes
state.sobelLimit = 0;
state.sadThreshold = 255;
break;
case 'I':
state.check_horizontal_invariance = !state.check_horizontal_invariance;
break;
case '.':
recording_manager.SetPlaybackFrameNumber(recording_manager.GetFrameNumber() + 1);
break;
case ',':
recording_manager.SetPlaybackFrameNumber(recording_manager.GetFrameNumber() - 1);
break;
case '>':
recording_manager.SetPlaybackFrameNumber(recording_manager.GetFrameNumber() + 50);
break;
case '<':
recording_manager.SetPlaybackFrameNumber(recording_manager.GetFrameNumber() - 50);
break;
//case 'k':
// state.zero_dist_disparity ++;
// break;
case 'l':
state.zero_dist_disparity --;
break;
case 'o':
inf_sad_add --;
break;
case 'p':
inf_sad_add ++;
break;
case '[':
y_offset --;
if (y_offset < 0) {
y_offset = 0;
}
break;
case ']':
y_offset ++;
break;
case 'v':
display_hud = !display_hud;
break;
case 'c':
hud.SetClutterLevel(hud.GetClutterLevel() + 1);
break;
case 'C':
hud.SetClutterLevel(hud.GetClutterLevel() - 1);
break;
case '}':
hud.SetPitchRangeOfLens(hud.GetPitchRangeOfLens() + 1);
break;
case '{':
hud.SetPitchRangeOfLens(hud.GetPitchRangeOfLens() - 1);
break;
case 'S':
// take a screen cap of the left and right images
// useful for putting into a stereo tuner
printf("\nWriting left.ppm...");
imwrite("left.ppm", remapL);
printf("\nWriting right.ppm...");
imwrite("right.ppm", remapR);
printf("\ndone.");
break;
case 'V':
// record the HUD
record_hud = true;
recording_manager.RestartRecHud();
break;
/*
case 'j':
state.debugJ --;
break;
case 'J':
state.debugJ ++;
break;
case 'i':
state.debugI --;
break;
case 'I':
state.debugI ++;
break;
case 'k':
state.debugDisparity --;
break;
case 'K':
state.debugDisparity ++;
break;
*/
case 'q':
quit = true;
break;
}
if (key != 255 && key != -1)
{
cout << "sadThreshold = " << state.sadThreshold << endl;
cout << "sobelLimit = " << state.sobelLimit << endl;
cout << "horizontalInvarianceMultiplier = " << state.horizontalInvarianceMultiplier << endl;
cout << "brightness: " << force_brightness << endl;
cout << "exposure: " << force_exposure << endl;
cout << "disparity = " << state.disparity << endl;
cout << "inf_disparity = " << state.zero_dist_disparity << endl;
cout << "inf_sad_add = " << inf_sad_add << endl;
cout << "blockSize = " << state.blockSize << endl;
cout << "frame_number = " << recording_manager.GetFrameNumber() << endl;
cout << "y offset = " << y_offset << endl;
cout << "PitchRangeOfLens = " << hud.GetPitchRangeOfLens() << endl;
}
} // end show_display
numFrames ++;
// check for new LCM messages
NonBlockingLcm(lcm);
if (quiet_mode == false || numFrames % 100 == 0) {
// compute framerate
gettimeofday( &now, NULL );
elapsed = (now.tv_usec / 1000 + now.tv_sec * 1000) -
(start.tv_usec / 1000 + start.tv_sec * 1000);
printf("\r%d frames (%lu ms) - %4.1f fps | %4.1f ms/frame, stereo: %f", numFrames, elapsed, (float)numFrames/elapsed * 1000, elapsed/(float)numFrames, timer_sum/(double)timer_count);
fflush(stdout);
}
} // end main while loop
printf("\n\n");
destroyWindow("Input");
destroyWindow("Input2");
destroyWindow("Stereo");
// close camera
if (recording_manager.UsingLiveCameras()) {
StopCapture(d, camera);
StopCapture(d2, camera2);
}
return 0;
}
/**
* Mouse callback so that the user can click on an image
* and see where the disparity line is on the other image pair
*/
void onMouse( int event, int x, int y, int flags, void* )
{
if( flags & CV_EVENT_FLAG_LBUTTON)
{
// paint a line on the image they clicked on
lineLeftImgPosition = x;
lineLeftImgPositionY = y;
cout << x << ", " << y << endl;
}
}
/**
* Mouse callback for the stereo image so that the user can click on an image
* and see where the disparity line is on the other image pair
*/
void onMouseStereo( int event, int x, int y, int flags, void* hud) {
Hud *hud_in = (Hud*) hud;
if( flags & CV_EVENT_FLAG_LBUTTON)
{
state.debugI = y;
state.debugJ = x;
// paint a line on the image they clicked on
if (display_hud) {
// check for scaling on the hud
lineLeftImgPosition = x / hud_in->GetImageScaling();
lineLeftImgPositionY = y / hud_in->GetImageScaling();
} else {
lineLeftImgPosition = x;
lineLeftImgPositionY = y;
}
}
}
/**
* Draws lines on the images for stereo debugging.
*
* @param rightImg right image
* @param stereoImg stereo image
* @param lineX x position of the line to draw
* @param lineY y position of the line to draw
* @param disparity disparity move the line on the right image over by
* @param inf_disparity disparity corresponding to "infinite distance"
* used to filter out false-positives. Usually availible in
* state.zero_dist_disparity.
*/
void DrawLines(Mat leftImg, Mat rightImg, Mat stereoImg, int lineX, int lineY, int disparity, int inf_disparity) {
int lineColor = 128;
if (lineX >= 0)
{
// print out the values of the pixels where they clicked
//cout << endl << endl << "Left px: " << (int)leftImg.at<uchar>(lineY, lineX)
// << "\tRight px: " << (int)rightImg.at<uchar>(lineY, lineX + disparity)
// << endl;
line(leftImg, Point(lineX, 0), Point(lineX, leftImg.rows), lineColor);
line(stereoImg, Point(lineX, 0), Point(lineX, leftImg.rows), lineColor);
line(rightImg, Point(lineX + disparity, 0), Point(lineX + disparity, rightImg.rows), lineColor);
line(rightImg, Point(lineX + inf_disparity, 0), Point(lineX + inf_disparity, rightImg.rows), lineColor);
line(leftImg, Point(0, lineY), Point(leftImg.cols, lineY), lineColor);
line(stereoImg, Point(0, lineY), Point(leftImg.cols, lineY), lineColor);
line(rightImg, Point(0, lineY), Point(rightImg.cols, lineY), lineColor);
}
}
/**
* Writes a disparity map in the style of a normal stereo vision system
*
* @param pointVector2d output from stereo algorithm
* @param state PushbroomStereoState used to process stereo
* @param pixel_value value to fill in this round of pixels, from 0 to 255
* @default 128
* @param existing_map provide this if you want to write on top of an existing
* image. Must be 376x240, CV_8UC1.
* @default Mat::zeros(240, 376, CV_8UC1);
*
* @retval a Mat that contains the single disparity map. It is CV_8UC1 and