-
Notifications
You must be signed in to change notification settings - Fork 400
/
misc.cpp
1257 lines (1130 loc) · 55.2 KB
/
misc.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
/* This file is part of RGBDSLAM.
*
* RGBDSLAM is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* RGBDSLAM is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with RGBDSLAM. If not, see <http://www.gnu.org/licenses/>.
*/
#include <ros/ros.h>
#include <tf/transform_datatypes.h>
#include <Eigen/Core>
#include <QString>
#include <QMatrix4x4>
#include <ctime>
#include <limits>
#include <algorithm>
#include "parameter_server.h"
#include <cv.h>
#include "scoped_timer.h"
#include "header.h"
#include "g2o/types/slam3d/se3quat.h"
#include "g2o/types/slam3d/vertex_se3.h"
#include <pcl_ros/transforms.h>
#include "pcl/common/io.h"
#include "pcl/common/distances.h"
#if CV_MAJOR_VERSION > 2 || CV_MINOR_VERSION >= 4
#include "opencv2/core/core.hpp"
#include "opencv2/features2d/features2d.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "opencv2/nonfree/nonfree.hpp"
#endif
#include <omp.h>
#include "misc2.h"
#include "point_types.h"
//For the observability test
#include <boost/math/distributions/chi_squared.hpp>
#include <numeric>
void printQMatrix4x4(const char* name, const QMatrix4x4& m){
ROS_DEBUG("QMatrix %s:", name);
ROS_DEBUG("%f\t%f\t%f\t%f", m(0,0), m(0,1), m(0,2), m(0,3));
ROS_DEBUG("%f\t%f\t%f\t%f", m(1,0), m(1,1), m(1,2), m(1,3));
ROS_DEBUG("%f\t%f\t%f\t%f", m(2,0), m(2,1), m(2,2), m(2,3));
ROS_DEBUG("%f\t%f\t%f\t%f", m(3,0), m(3,1), m(3,2), m(3,3));
}
void printTransform(const char* name, const tf::Transform t) {
ROS_INFO_STREAM(name << ": Translation " << t.getOrigin().x() << " " << t.getOrigin().y() << " " << t.getOrigin().z());
ROS_INFO_STREAM(name << ": Rotation " << t.getRotation().getX() << " " << t.getRotation().getY() << " " << t.getRotation().getZ() << " " << t.getRotation().getW());
}
void logTransform(QTextStream& out, const tf::Transform& t, double timestamp, const char* label) {
if(label) out << label << ": ";
out << timestamp << " " << t.getOrigin().x() << " " << t.getOrigin().y() << " " << t.getOrigin().z() << " " << t.getRotation().getX() << " " << t.getRotation().getY() << " " << t.getRotation().getZ() << " " << t.getRotation().getW() << "\n";
}
QMatrix4x4 g2o2QMatrix(const g2o::SE3Quat se3) {
Eigen::Matrix<double, 4, 4> m = se3.to_homogeneous_matrix(); //_Matrix< 4, 4, double >
ROS_DEBUG_STREAM("Eigen Matrix:\n" << m);
QMatrix4x4 qmat( static_cast<qreal*>( m.data() ) );
// g2o/Eigen seems to use a different row-major/column-major array layout
printQMatrix4x4("from conversion", qmat.transposed());//thus the transposes
return qmat.transposed();//thus the transposes
}
tf::Transform g2o2TF(const g2o::SE3Quat se3) {
tf::Transform result;
tf::Vector3 translation;
translation.setX(se3.translation().x());
translation.setY(se3.translation().y());
translation.setZ(se3.translation().z());
tf::Quaternion rotation;
rotation.setX(se3.rotation().x());
rotation.setY(se3.rotation().y());
rotation.setZ(se3.rotation().z());
rotation.setW(se3.rotation().w());
result.setOrigin(translation);
result.setRotation(rotation);
//printTransform("from conversion", result);
return result;
}
void transformAndAppendPointCloud (const pointcloud_type &cloud_in,
pcl::PointCloud<hema::PointXYZRGBCamSL> &cloud_to_append_to,
const tf::Transform transformation, float max_Depth, int idx)
{
Eigen::Matrix4f eigen_transform;
pcl_ros::transformAsMatrix(transformation, eigen_transform);
size_t original_size = cloud_to_append_to.size();
cloud_to_append_to.points.reserve(cloud_in.size()+original_size);
if(cloud_to_append_to.points.size() ==0){
cloud_to_append_to.header = cloud_in.header;
cloud_to_append_to.width = 0;
cloud_to_append_to.height = 0;
cloud_to_append_to.is_dense = false;
}
Eigen::Matrix3f rot = eigen_transform.block<3, 3> (0, 0);
Eigen::Vector3f trans = eigen_transform.block<3, 1> (0, 3);
size_t i = 0;
for (; i < cloud_in.points.size (); ++i)
{
const point_type& in_pt = cloud_in[i];
const Eigen::Map<Eigen::Vector3f> vec_in (const_cast<float*>(&in_pt.x), 3, 1);
hema::PointXYZRGBCamSL out_pt;
Eigen::Map<Eigen::Vector3f> vec_out (&out_pt.x, 3, 1);
//filter out points with a range greater than the given Parameter or do nothing if negativ
float distance = vec_in.norm();
out_pt.distance = distance;
out_pt.cameraIndex = idx;
out_pt.segment = 0;
out_pt.label = 0;
#ifndef RGB_IS_4TH_DIM
out_pt.rgb = in_pt.rgb;
#else
out_pt.data[3] = in_pt.data[3];
#endif
if(max_Depth >= 0 && max_Depth > distance){//Erase coordinates high-noise points if desired
vec_out[0]= vec_out[1]= vec_out[2]= std::numeric_limits<float>::quiet_NaN();
}
vec_out = rot * vec_in + trans;//Might be nan, but whatever
cloud_to_append_to.push_back(out_pt);
}
}
//From: /opt/ros/unstable/stacks/perception_pcl/pcl/src/pcl/registration/transforms.hpp
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
/** \brief Apply an affine transform defined by an Eigen Transform
* \param cloud_in the input point cloud
* \param cloud_to_append_to the transformed cloud will be appended to this one
* \param transform a tf::Transform stating the transformation of cloud_to_append_to relative to cloud_in
* \note The density of the point cloud is lost, if parameter preserve_raster_on_save is set, as NaNs will be copied to keep raster structure
* \note Can not(?) be used with cloud_in equal to cloud_to_append_to
*/
//template <typename PointT> void
//transformAndAppendPointCloud (const pcl::PointCloud<PointT> &cloud_in, pcl::PointCloud<PointT> &cloud_to_append_to,
// const tf::Transform transformation)
void transformAndAppendPointCloud (const pointcloud_type &cloud_in,
pointcloud_type &cloud_to_append_to,
const tf::Transform transformation, float max_Depth, int )
{
bool compact = !ParameterServer::instance()->get<bool>("preserve_raster_on_save");
Eigen::Matrix4f eigen_transform;
pcl_ros::transformAsMatrix(transformation, eigen_transform);
unsigned int cloud_to_append_to_original_size = cloud_to_append_to.size();
if(cloud_to_append_to.points.size() ==0){
cloud_to_append_to.header = cloud_in.header;
cloud_to_append_to.width = 0;
cloud_to_append_to.height = 0;
cloud_to_append_to.is_dense = false;
}
ROS_DEBUG("max_Depth = %f", max_Depth);
ROS_DEBUG("cloud_to_append_to_original_size = %i", cloud_to_append_to_original_size);
//Append all points untransformed. This also copies other fields, e.g rgb
cloud_to_append_to += cloud_in;
Eigen::Matrix3f rot = eigen_transform.block<3, 3> (0, 0);
Eigen::Vector3f trans = eigen_transform.block<3, 1> (0, 3);
point_type origin = point_type();
origin.x = 0;
origin.y = 0;
origin.z = 0;
int j = 0;
for (size_t i = 0; i < cloud_in.points.size (); ++i)
{
Eigen::Map<Eigen::Vector3f> p_in (const_cast<float*>(&cloud_in.points[i].x), 3, 1);
Eigen::Map<Eigen::Vector3f> p_out (&cloud_to_append_to.points[j+cloud_to_append_to_original_size].x, 3, 1);
if(compact){ cloud_to_append_to.points[j+cloud_to_append_to_original_size] = cloud_in.points[i]; }
//filter out points with a range greater than the given Parameter or do nothing if negativ
if(max_Depth >= 0){
if(pcl::squaredEuclideanDistance(cloud_in.points[i], origin) > max_Depth*max_Depth){
p_out[0]= std::numeric_limits<float>::quiet_NaN();
p_out[1]= std::numeric_limits<float>::quiet_NaN();
p_out[2]= std::numeric_limits<float>::quiet_NaN();
if(!compact) j++;
continue;
}
}
if (pcl_isnan (cloud_in.points[i].x) || pcl_isnan (cloud_in.points[i].y) || pcl_isnan (cloud_in.points[i].z)){
if(!compact) j++;
continue;
}
p_out = rot * p_in + trans;
j++;
}
if(compact){
cloud_to_append_to.points.resize(j+cloud_to_append_to_original_size);
cloud_to_append_to.width = 1;
cloud_to_append_to.height = j+cloud_to_append_to_original_size;
}
}
//do spurious type conversions
geometry_msgs::Point pointInWorldFrame(const Eigen::Vector4f& point3d, const g2o::VertexSE3::EstimateType& transf)
{
Eigen::Vector3d tmp(point3d[0], point3d[1], point3d[2]);
tmp = transf * tmp; //transform to world frame
geometry_msgs::Point p;
p.x = tmp.x();
p.y = tmp.y();
p.z = tmp.z();
return p;
}
void mat2dist(const Eigen::Matrix4f& t, double &dist){
dist = sqrt(t(0,3)*t(0,3)+t(1,3)*t(1,3)+t(2,3)*t(2,3));
}
///Get euler angles from affine matrix (helper for isBigTrafo)
void mat2RPY(const Eigen::Matrix4f& t, double& roll, double& pitch, double& yaw) {
roll = atan2(t(2,1),t(2,2));
pitch = atan2(-t(2,0),sqrt(t(2,1)*t(2,1)+t(2,2)*t(2,2)));
yaw = atan2(t(1,0),t(0,0));
}
void mat2components(const Eigen::Matrix4f& t, double& roll, double& pitch, double& yaw, double& dist){
mat2RPY(t, roll,pitch,yaw);
mat2dist(t, dist);
roll = roll/M_PI*180;
pitch = pitch/M_PI*180;
yaw = yaw/M_PI*180;
}
void trafoSize(const Eigen::Isometry3d& t, double& angle, double& dist){
angle = acos((t.rotation().trace() -1)/2 ) *180.0 / M_PI;
dist = t.translation().norm();
ROS_INFO("Rotation:% 4.2f, Distance: % 4.3fm", angle, dist);
}
bool isBigTrafo(const Eigen::Isometry3d& t){
double angle, dist;
trafoSize(t, angle, dist);
return (dist > ParameterServer::instance()->get<double>("min_translation_meter") ||
angle > ParameterServer::instance()->get<double>("min_rotation_degree"));
}
// true iff edge qualifies for generating a new vertex
bool isBigTrafo(const Eigen::Matrix4f& t){
double roll, pitch, yaw, dist;
mat2RPY(t, roll,pitch,yaw);
mat2dist(t, dist);
roll = roll/M_PI*180;
pitch = pitch/M_PI*180;
yaw = yaw/M_PI*180;
double max_angle = std::max(roll,std::max(pitch,yaw));
return (dist > ParameterServer::instance()->get<double>("min_translation_meter")
|| max_angle > ParameterServer::instance()->get<double>("min_rotation_degree"));
}
bool isSmallTrafo(const Eigen::Isometry3d& t, double seconds){
if(seconds <= 0.0){
ROS_WARN("Time delta invalid: %f. Skipping test for small transformation", seconds);
return true;
}
double angle_around_axis, dist;
trafoSize(t, angle_around_axis, dist);
ParameterServer* ps = ParameterServer::instance();
return (dist / seconds < ps->get<double>("max_translation_meter") &&
angle_around_axis / seconds < ps->get<int>("max_rotation_degree"));
}
bool isSmallTrafo(const g2o::SE3Quat& t, double seconds){
if(seconds <= 0.0){
ROS_WARN("Time delta invalid: %f. Skipping test for small transformation", seconds);
return true;
}
float angle_around_axis = 2.0*acos(t.rotation().w()) *180.0 / M_PI;
float dist = t.translation().norm();
QString infostring;
ROS_INFO("Rotation:% 4.2f, Distance: % 4.3fm", angle_around_axis, dist);
infostring.sprintf("Rotation:% 4.2f, Distance: % 4.3fm", angle_around_axis, dist);
//Q_EMIT setGUIInfo2(infostring);
ParameterServer* ps = ParameterServer::instance();
//Too big fails too
return (dist / seconds < ps->get<double>("max_translation_meter") &&
angle_around_axis / seconds < ps->get<int>("max_rotation_degree"));
}
bool isBigTrafo(const g2o::SE3Quat& t){
float angle_around_axis = 2.0*acos(t.rotation().w()) *180.0 / M_PI;
float dist = t.translation().norm();
QString infostring;
ROS_INFO("Rotation:% 4.2f, Distance: % 4.3fm", angle_around_axis, dist);
infostring.sprintf("Rotation:% 4.2f, Distance: % 4.3fm", angle_around_axis, dist);
//Q_EMIT setGUIInfo2(infostring);
ParameterServer* ps = ParameterServer::instance();
return (dist > ps->get<double>("min_translation_meter") ||
angle_around_axis > ps->get<double>("min_rotation_degree"));
}
/*
bool overlappingViews(LoadedEdge3D edge){
//opening angles
double alpha = 57.0/180.0*M_PI;
double beta = 47.0/180.0*M_PI;
//assumes robot coordinate system (x is front, y is left, z is up)
Eigen::Matrix<double, 4,3> cam1;
cam1 << 1.0, std::tan(alpha), std::tan(beta),//upper left
1.0, -std::tan(alpha), std::tan(beta),//upper right
1.0, std::tan(alpha), -std::tan(beta),//lower left
1.0, -std::tan(alpha),-std::tan(beta);//lower right
return false;
}
bool triangleRayIntersection(Eigen::Vector3d triangle1,Eigen::Vector3d triangle2,
Eigen::Vector3d ray_origin, Eigen::Vector3d ray){
Eigen::Matrix3d m;
m.col(2) = -ray;
m.col(0) = triangle1;
m.col(1) = triangle2;
Eigen::Vector3d lengths = m.inverse() * ray_origin;
return (lengths(0) < 0 && lengths(1) > 0 && lengths(2) > 0 );
}
*/
g2o::SE3Quat tf2G2O(const tf::Transform t)
{
Eigen::Quaterniond eigen_quat(t.getRotation().getW(), t.getRotation().getX(), t.getRotation().getY(), t.getRotation().getZ());
Eigen::Vector3d translation(t.getOrigin().x(), t.getOrigin().y(), t.getOrigin().z());
g2o::SE3Quat result(eigen_quat, translation);
return result;
}
g2o::SE3Quat eigen2G2O(const Eigen::Matrix4d& eigen_mat)
{
Eigen::Affine3d eigen_transform(eigen_mat);
Eigen::Quaterniond eigen_quat(eigen_transform.rotation());
Eigen::Vector3d translation(eigen_mat(0, 3), eigen_mat(1, 3), eigen_mat(2, 3));
g2o::SE3Quat result(eigen_quat, translation);
return result;
}
using namespace cv;
///Analog to opencv example file and modified to use adjusters
FeatureDetector* createDetector( const string& detectorType )
{
ParameterServer* params = ParameterServer::instance();
FeatureDetector* fd = 0;
if( !detectorType.compare( "FAST" ) ) {
//fd = new FastFeatureDetector( 20/*threshold*/, true/*nonmax_suppression*/ );
fd = new DynamicAdaptedFeatureDetector (new FastAdjuster(20,true),
params->get<int>("min_keypoints"),
params->get<int>("max_keypoints"),
params->get<int>("adjuster_max_iterations"));
}
else if( !detectorType.compare( "STAR" ) ) {
fd = new StarFeatureDetector( 16/*max_size*/, 5/*response_threshold*/, 10/*line_threshold_projected*/,
8/*line_threshold_binarized*/, 5/*suppress_nonmax_size*/ );
}
else if( !detectorType.compare( "SIFT" ) ) {
#if CV_MAJOR_VERSION > 2 || CV_MINOR_VERSION <= 3
fd = new SiftFeatureDetector(SIFT::DetectorParams::GET_DEFAULT_THRESHOLD(),
SIFT::DetectorParams::GET_DEFAULT_EDGE_THRESHOLD());
ROS_INFO("Default SIFT threshold: %f, Default SIFT Edge Threshold: %f",
SIFT::DetectorParams::GET_DEFAULT_THRESHOLD(),
SIFT::DetectorParams::GET_DEFAULT_EDGE_THRESHOLD());
#else
fd = new SiftFeatureDetector();
#endif
}
else if( !detectorType.compare( "SURF" ) ) {
/* fd = new SurfFeatureDetector(200.0, 6, 5); */
fd = new DynamicAdaptedFeatureDetector(new SurfAdjuster(),
params->get<int>("min_keypoints"),
params->get<int>("max_keypoints")+300,
params->get<int>("adjuster_max_iterations"));
}
else if( !detectorType.compare( "MSER" ) ) {
fd = new MserFeatureDetector( 1/*delta*/, 60/*min_area*/, 114400/*_max_area*/, 0.35f/*max_variation*/,
0.2/*min_diversity*/, 200/*max_evolution*/, 1.01/*area_threshold*/, 0.003/*min_margin*/,
5/*edge_blur_size*/ );
}
else if( !detectorType.compare( "GFTT" ) ) {
ROS_INFO("Creating GFTT detector as fallback.");
fd = new GoodFeaturesToTrackDetector( params->get<int>("max_keypoints"), 0.0001, 2.0, 9);
}
else if( !detectorType.compare( "ORB" ) ) {
#if CV_MAJOR_VERSION > 2 || CV_MINOR_VERSION == 3
fd = new OrbFeatureDetector(params->get<int>("max_keypoints")+1500,
ORB::CommonParams(1.2, ORB::CommonParams::DEFAULT_N_LEVELS, 31, ORB::CommonParams::DEFAULT_FIRST_LEVEL));
#elif CV_MAJOR_VERSION > 2 || CV_MINOR_VERSION >= 4
fd = new OrbFeatureDetector();
#else
ROS_ERROR("ORB features are not implemented in your version of OpenCV");
#endif
}
else if( !detectorType.compare( "SIFTGPU" ) ) {
ROS_INFO("%s is to be used", detectorType.c_str());
ROS_DEBUG("Creating SURF detector as fallback.");
fd = createDetector("SURF"); //recursive call with correct parameter
}
else {
ROS_WARN("No valid detector-type given: %s. Using SURF.", detectorType.c_str());
fd = createDetector("SURF"); //recursive call with correct parameter
}
ROS_ERROR_COND(fd == 0, "No detector could be created");
return fd;
}
DescriptorExtractor* createDescriptorExtractor( const string& descriptorType )
{
DescriptorExtractor* extractor = 0;
if( !descriptorType.compare( "SIFT" ) ) {
extractor = new SiftDescriptorExtractor();/*( double magnification=SIFT::DescriptorParams::GET_DEFAULT_MAGNIFICATION(), bool isNormalize=true, bool recalculateAngles=true, int nOctaves=SIFT::CommonParams::DEFAULT_NOCTAVES, int nOctaveLayers=SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS, int firstOctave=SIFT::CommonParams::DEFAULT_FIRST_OCTAVE, int angleMode=SIFT::CommonParams::FIRST_ANGLE )*/
}
else if( !descriptorType.compare( "SURF" ) ) {
extractor = new SurfDescriptorExtractor();/*( int nOctaves=4, int nOctaveLayers=2, bool extended=false )*/
}
#if CV_MAJOR_VERSION > 2 || CV_MINOR_VERSION >= 3
else if( !descriptorType.compare( "ORB" ) ) {
extractor = new OrbDescriptorExtractor();
}
#endif
else if( !descriptorType.compare( "SIFTGPU" ) ) {
ROS_INFO("%s is to be used as extractor, creating SURF descriptor extractor as fallback.", descriptorType.c_str());
extractor = new SurfDescriptorExtractor();/*( int nOctaves=4, int nOctaveLayers=2, bool extended=false )*/
}
else {
ROS_ERROR("No valid descriptor-matcher-type given: %s. Using SURF", descriptorType.c_str());
extractor = createDescriptorExtractor("SURF");
}
ROS_ERROR_COND(extractor == 0, "No extractor could be created");
return extractor;
}
//Little debugging helper functions
std::string openCVCode2String(unsigned int code){
switch(code){
case 0 : return std::string("CV_8UC1" );
case 8 : return std::string("CV_8UC2" );
case 16: return std::string("CV_8UC3" );
case 24: return std::string("CV_8UC4" );
case 2 : return std::string("CV_16UC1");
case 10: return std::string("CV_16UC2");
case 18: return std::string("CV_16UC3");
case 26: return std::string("CV_16UC4");
case 5 : return std::string("CV_32FC1");
case 13: return std::string("CV_32FC2");
case 21: return std::string("CV_32FC3");
case 29: return std::string("CV_32FC4");
}
return std::string("Unknown");
}
void printMatrixInfo(cv::Mat& image, std::string name){
ROS_INFO_STREAM("Matrix " << name << " - Type:" << openCVCode2String(image.type()) << " rows: " << image.rows << " cols: " << image.cols);
}
void depthToCV8UC1(cv::Mat& depth_img, cv::Mat& mono8_img){
//Process images
if(depth_img.type() == CV_32FC1){
depth_img.convertTo(mono8_img, CV_8UC1, 100,0); //milimeter (scale of mono8_img does not matter)
}
else if(depth_img.type() == CV_16UC1){
mono8_img = cv::Mat(depth_img.size(), CV_8UC1);
cv::Mat float_img;
depth_img.convertTo(mono8_img, CV_8UC1, 0.05, -25); //scale to 2cm
depth_img.convertTo(float_img, CV_32FC1, 0.001, 0);//From mm to m(scale of depth_img matters)
depth_img = float_img;
}
else {
printMatrixInfo(depth_img, "Depth Image");
ROS_ERROR_STREAM("Don't know how to handle depth image of type "<< openCVCode2String(depth_img.type()));
}
}
bool asyncFrameDrop(ros::Time depth, ros::Time rgb)
{
long rgb_timediff = abs(static_cast<long>(rgb.nsec) - static_cast<long>(depth.nsec));
if(rgb_timediff > 33333333){
ROS_DEBUG("Depth image time: %d - %d", depth.sec, depth.nsec);
ROS_DEBUG("RGB image time: %d - %d", rgb.sec, rgb.nsec);
ROS_INFO("Depth and RGB image off more than 1/30sec: %li (nsec)", rgb_timediff);
if(ParameterServer::instance()->get<bool>("drop_async_frames")){
ROS_WARN("Asynchronous frames ignored. See parameters if you want to keep async frames.");
return true;
}
} else {
ROS_DEBUG("Depth image time: %d - %d", depth.sec, depth.nsec);
ROS_DEBUG("RGB image time: %d - %d", rgb.sec, rgb.nsec);
}
return false;
}
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
///\cond
/** Union for easy "conversion" of rgba data */
typedef union
{
struct /*anonymous*/
{
unsigned char Blue;
unsigned char Green;
unsigned char Red;
unsigned char Alpha;
};
float float_value;
long long_value;
} RGBValue;
///\endcond
pointcloud_type* createXYZRGBPointCloud (const cv::Mat& depth_img,
const cv::Mat& rgb_img,
const sensor_msgs::CameraInfoConstPtr& cam_info)
{
ScopedTimer s(__FUNCTION__);
pointcloud_type* cloud (new pointcloud_type() );
cloud->is_dense = false; //single point of view, 2d rasterized NaN where no depth value was found
ParameterServer* ps = ParameterServer::instance();
float fx = 1./ (ps->get<double>("depth_camera_fx") > 0 ? ps->get<double>("depth_camera_fx") : cam_info->K[0]); //(cloud->width >> 1) - 0.5f;
float fy = 1./ (ps->get<double>("depth_camera_fy") > 0 ? ps->get<double>("depth_camera_fy") : cam_info->K[4]); //(cloud->width >> 1) - 0.5f;
float cx = ps->get<double>("depth_camera_cx") > 0 ? ps->get<double>("depth_camera_cx") : cam_info->K[2]; //(cloud->width >> 1) - 0.5f;
float cy = ps->get<double>("depth_camera_cy") > 0 ? ps->get<double>("depth_camera_cy") : cam_info->K[5]; //(cloud->width >> 1) - 0.5f;
int data_skip_step = ParameterServer::instance()->get<int>("cloud_creation_skip_step");
if(depth_img.rows % data_skip_step != 0 || depth_img.cols % data_skip_step != 0){
ROS_WARN("The parameter cloud_creation_skip_step is not a divisor of the depth image dimensions. This will most likely crash the program!");
}
cloud->height = ceil(depth_img.rows / static_cast<float>(data_skip_step));
cloud->width = ceil(depth_img.cols / static_cast<float>(data_skip_step));
//cx = cam_info->K[2]; //(cloud->width >> 1) - 0.5f;
//cy = cam_info->K[5]; //(cloud->height >> 1) - 0.5f;
//fx = 1.0f / cam_info->K[0];
//fy = 1.0f / cam_info->K[4];
int pixel_data_size = 3;
//Assume BGR
//char red_idx = 2, green_idx = 1, blue_idx = 0;
//Assume RGB
char red_idx = 0, green_idx = 1, blue_idx = 2;
if(rgb_img.type() == CV_8UC1) pixel_data_size = 1;
else if(ParameterServer::instance()->get<bool>("encoding_bgr")) { red_idx = 2; blue_idx = 0; }
unsigned int color_row_step, color_pix_step, depth_pix_step, depth_row_step;
color_pix_step = pixel_data_size * (rgb_img.cols / cloud->width);
color_row_step = pixel_data_size * (rgb_img.rows / cloud->height -1 ) * rgb_img.cols;
depth_pix_step = (depth_img.cols / cloud->width);
depth_row_step = (depth_img.rows / cloud->height -1 ) * depth_img.cols;
cloud->points.resize (cloud->height * cloud->width);
//const uint8_t* rgb_buffer = &rgb_msg->data[0];
// depth_img already has the desired dimensions, but rgb_img may be higher res.
int color_idx = 0 * color_pix_step - 0 * color_row_step, depth_idx = 0; //FIXME: Hack for hard-coded calibration of color to depth
double depth_scaling = ParameterServer::instance()->get<double>("depth_scaling_factor");
float max_depth = ParameterServer::instance()->get<double>("maximum_depth");
float min_depth = ParameterServer::instance()->get<double>("minimum_depth");
if(max_depth < 0.0) max_depth = std::numeric_limits<float>::infinity();
pointcloud_type::iterator pt_iter = cloud->begin();
for (int v = 0; v < (int)rgb_img.rows; v += data_skip_step, color_idx += color_row_step, depth_idx += depth_row_step)
{
for (int u = 0; u < (int)rgb_img.cols; u += data_skip_step, color_idx += color_pix_step, depth_idx += depth_pix_step, ++pt_iter)
{
if(pt_iter == cloud->end()){
break;
}
point_type& pt = *pt_iter;
if(u < 0 || v < 0 || u >= depth_img.cols || v >= depth_img.rows){
pt.x = std::numeric_limits<float>::quiet_NaN();
pt.y = std::numeric_limits<float>::quiet_NaN();
pt.z = std::numeric_limits<float>::quiet_NaN();
continue;
}
float Z = depth_img.at<float>(depth_idx) * depth_scaling;
// Check for invalid measurements
if (!(Z >= min_depth)) //Should also be trigger on NaN//std::isnan (Z))
{
pt.x = (u - cx) * 1.0 * fx; //FIXME: better solution as to act as at 1meter?
pt.y = (v - cy) * 1.0 * fy;
pt.z = std::numeric_limits<float>::quiet_NaN();
}
else // Fill in XYZ
{
pt.x = (u - cx) * Z * fx;
pt.y = (v - cy) * Z * fy;
pt.z = Z;
}
// Fill in color
RGBValue color;
if(color_idx > 0 && color_idx < rgb_img.total()*color_pix_step){ //Only necessary because of the color_idx offset
if(pixel_data_size == 3){
color.Red = rgb_img.at<uint8_t>(color_idx + red_idx);
color.Green = rgb_img.at<uint8_t>(color_idx + green_idx);
color.Blue = rgb_img.at<uint8_t>(color_idx + blue_idx);
} else {
color.Red = color.Green = color.Blue = rgb_img.at<uint8_t>(color_idx);
}
color.Alpha = 0;
#ifndef RGB_IS_4TH_DIM
pt.rgb = color.float_value;
#else
pt.data[3] = color.float_value;
#endif
}
}
}
return cloud;
}
pointcloud_type* createXYZRGBPointCloud (const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::ImageConstPtr& rgb_msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
{
ScopedTimer s(__FUNCTION__);
pointcloud_type* cloud (new pointcloud_type() );
myHeader h(0, depth_msg->header.stamp, rgb_msg->header.frame_id);
cloud->header = h;
//cloud->header.stamp = depth_msg->header.stamp;
//cloud->header.frame_id = rgb_msg->header.frame_id;
cloud->is_dense = false; //single point of view, 2d rasterized NaN where no depth value was found
ParameterServer* ps = ParameterServer::instance();
float fx = ps->get<double>("depth_camera_fx") > 0 ? ps->get<double>("depth_camera_fx") : cam_info->K[0]; //(cloud->width >> 1) - 0.5f;
float fy = ps->get<double>("depth_camera_fy") > 0 ? ps->get<double>("depth_camera_fy") : cam_info->K[4]; //(cloud->width >> 1) - 0.5f;
float cx = ps->get<double>("depth_camera_cx") > 0 ? ps->get<double>("depth_camera_cx") : cam_info->K[2]; //(cloud->width >> 1) - 0.5f;
float cy = ps->get<double>("depth_camera_cy") > 0 ? ps->get<double>("depth_camera_cy") : cam_info->K[5]; //(cloud->width >> 1) - 0.5f;
int data_skip_step = ps->get<int>("cloud_creation_skip_step");
cloud->height = depth_msg->height / data_skip_step;
cloud->width = depth_msg->width / data_skip_step;
//Reciprocal to use multiplication in loop, not slower division
fx = 1.0f / fx;//1.0f / cam_info->K[0];
fy = 1.0f / fy;//1.0f / cam_info->K[4];
int pixel_data_size = 3;
char red_idx = 0, green_idx = 1, blue_idx = 2;
if(rgb_msg->encoding.compare("mono8") == 0) pixel_data_size = 1;
if(rgb_msg->encoding.compare("bgr8") == 0) { red_idx = 2; blue_idx = 0; }
ROS_ERROR_COND(pixel_data_size == 0, "Unknown image encoding: %s!", rgb_msg->encoding.c_str());
unsigned int color_row_step, color_pix_step, depth_pix_step, depth_row_step;
color_pix_step = pixel_data_size * (rgb_msg->width / cloud->width);
color_row_step = pixel_data_size * (rgb_msg->height / cloud->height -1 ) * rgb_msg->width;
depth_pix_step = (depth_msg->width / cloud->width);
depth_row_step = (depth_msg->height / cloud->height -1 ) * depth_msg->width;
cloud->points.resize (cloud->height * cloud->width);
const uint8_t* rgb_buffer = &rgb_msg->data[0];
// depth_msg already has the desired dimensions, but rgb_msg may be higher res.
int color_idx = 0, depth_idx = 0;
double depth_scaling = ParameterServer::instance()->get<double>("depth_scaling_factor");
float max_depth = ParameterServer::instance()->get<double>("maximum_depth");
if(max_depth < 0.0) max_depth = std::numeric_limits<float>::infinity();
const float* depth_buffer = reinterpret_cast<const float*>(&depth_msg->data[0]);
pointcloud_type::iterator pt_iter = cloud->begin ();
for (int v = 0; v < (int)rgb_msg->height; v += data_skip_step, color_idx += color_row_step, depth_idx += depth_row_step)
{
for (int u = 0; u < (int)rgb_msg->width; u += data_skip_step, color_idx += color_pix_step, depth_idx += depth_pix_step, ++pt_iter)
{
point_type& pt = *pt_iter;
float Z = depth_buffer[depth_idx] * depth_scaling;
// Check for invalid measurements
if (!(Z <= max_depth)) //Should also be trigger on NaN//std::isnan (Z))
{
pt.x = (u - cx) * 1.0 * fx; //FIXME: better solution as to act as at 1meter?
pt.y = (v - cy) * 1.0 * fy;
pt.z = std::numeric_limits<float>::quiet_NaN();
}
else // Fill in XYZ
{
pt.x = (u - cx) * Z * fx;
pt.y = (v - cy) * Z * fy;
pt.z = Z;
}
// Fill in color
RGBValue color;
if(pixel_data_size == 3){
color.Red = rgb_buffer[color_idx + red_idx];
color.Green = rgb_buffer[color_idx + green_idx];
color.Blue = rgb_buffer[color_idx + blue_idx];
} else {
color.Red = color.Green = color.Blue = rgb_buffer[color_idx];
}
color.Alpha = 0;
#ifndef RGB_IS_4TH_DIM
pt.rgb = color.float_value;
#else
pt.data[3] = color.float_value;
#endif
}
}
return cloud;
}
double errorFunction(const Eigen::Vector4f& x1, const double x1_depth_cov,
const Eigen::Vector4f& x2, const double x2_depth_cov,
const Eigen::Matrix4f& tf_1_to_2)
{
const double cam_angle_x = 58.0/180.0*M_PI;
const double cam_angle_y = 45.0/180.0*M_PI;
const double cam_resol_x = 640;
const double cam_resol_y = 480;
const double raster_stddev_x = 2*tan(cam_angle_x/cam_resol_x); //2pix stddev in x
const double raster_stddev_y = 2*tan(cam_angle_y/cam_resol_y); //2pix stddev in y
const double raster_cov_x = raster_stddev_x * raster_stddev_x;
const double raster_cov_y = raster_stddev_y * raster_stddev_y;
ROS_DEBUG_COND(x1(3) != 1.0, "4th element of x1 should be 1.0, is %f", x1(3));
ROS_DEBUG_COND(x2(3) != 1.0, "4th element of x2 should be 1.0, is %f", x2(3));
Eigen::Vector3d mu_1 = x1.head<3>().cast<double>();
Eigen::Vector3d mu_2 = x2.head<3>().cast<double>();
Eigen::Matrix3d rotation_mat = tf_1_to_2.block(0,0,3,3).cast<double>();
//Point 1
Eigen::Matrix3d cov1 = Eigen::Matrix3d::Identity();
cov1(0,0) = raster_cov_x* mu_1(2); //how big is 1px std dev in meter, depends on depth
cov1(1,1) = raster_cov_y* mu_1(2); //how big is 1px std dev in meter, depends on depth
cov1(2,2) = x1_depth_cov;
//Point2
Eigen::Matrix3d cov2 = Eigen::Matrix3d::Identity();
cov2(0,0) = raster_cov_x* mu_2(2); //how big is 1px std dev in meter, depends on depth
cov2(1,1) = raster_cov_y* mu_2(2); //how big is 1px std dev in meter, depends on depth
cov2(2,2) = x2_depth_cov;
Eigen::Matrix3d cov2inv = cov2.inverse(); // Σ₂⁻¹
Eigen::Vector3d mu_1_in_frame_2 = (tf_1_to_2 * x1).head<3>().cast<double>(); // μ₁⁽²⁾ = T₁₂ μ₁⁽¹⁾
Eigen::Matrix3d cov1_in_frame_2 = rotation_mat.transpose() * cov1 * rotation_mat;//Works since the cov is diagonal => Eig-Vec-Matrix is Identity
Eigen::Matrix3d cov1inv_in_frame_2 = cov1_in_frame_2.inverse();// Σ₁⁻¹
Eigen::Matrix3d cov_sum = (cov1inv_in_frame_2 + cov2inv);
Eigen::Matrix3d inv_cov_sum = cov_sum.inverse();
ROS_ERROR_STREAM_COND(inv_cov_sum!=inv_cov_sum,"Sum of Covariances not invertible: \n" << cov_sum);
Eigen::Vector3d x_ml;//Max Likelhood Position of latent point, that caused the sensor msrmnt
x_ml = inv_cov_sum * (cov1inv_in_frame_2 * mu_1_in_frame_2 + cov2inv * mu_2); // (Σ₁⁻¹ + Σ₂⁻¹)⁻¹(Σ₁⁻¹μ₁ + Σ₂⁻¹μ₂)
Eigen::Vector3d delta_mu_1 = mu_1_in_frame_2 - x_ml;
Eigen::Vector3d delta_mu_2 = mu_2 - x_ml;
float sqrd_mahalanobis_distance1 = delta_mu_1.transpose() * cov1inv_in_frame_2 * delta_mu_1;// Δx_2^T Σ Δx_2
float sqrd_mahalanobis_distance2 = delta_mu_2.transpose() * cov2inv * delta_mu_2; // Δx_1^T Σ Δx_1
float bad_mahalanobis_distance = sqrd_mahalanobis_distance1 + sqrd_mahalanobis_distance2; //FIXME
if(!(bad_mahalanobis_distance >= 0.0))
{
ROS_ERROR_STREAM("Non-Positive Mahalanobis Distance");
return std::numeric_limits<double>::max();
}
ROS_DEBUG_STREAM_NAMED("statistics", "Mahalanobis ML: " << std::setprecision(25) << bad_mahalanobis_distance);
return bad_mahalanobis_distance;
}
double errorFunction2(const Eigen::Vector4f& x1,
const Eigen::Vector4f& x2,
const Eigen::Matrix4d& transformation)
{
ScopedTimer s(__FUNCTION__);
//FIXME: Take from paramter_server or cam info
static const double cam_angle_x = 58.0/180.0*M_PI;/*{{{*/
static const double cam_angle_y = 45.0/180.0*M_PI;
static const double cam_resol_x = 640;
static const double cam_resol_y = 480;
static const double raster_stddev_x = 3*tan(cam_angle_x/cam_resol_x); //5pix stddev in x
static const double raster_stddev_y = 3*tan(cam_angle_y/cam_resol_y); //5pix stddev in y
static const double raster_cov_x = raster_stddev_x * raster_stddev_x;
static const double raster_cov_y = raster_stddev_y * raster_stddev_y;/*}}}*/
static const bool use_error_shortcut = true;//ParameterServer::instance()->get<bool>("use_error_shortcut");
bool nan1 = isnan(x1(2));
bool nan2 = isnan(x2(2));
if(nan1||nan2){
//FIXME: Handle Features with NaN, by reporting the reprojection error
return std::numeric_limits<double>::max();
}
Eigen::Vector4d x_1 = x1.cast<double>();
Eigen::Vector4d x_2 = x2.cast<double>();
Eigen::Matrix4d tf_12 = transformation;
/* NaNs filtered before
if(nan1) x_1(2) = 1.0; //FIXME: Bad Hack
if(nan2) x_2(2) = 1.0; //FIXME: Bad Hack
if(nan1 && !nan2){ //If x_1 is nan, but not x_2, switch them, so the "good one" is transformed to the frame of the other
x_1 = x2.cast<double>();
x_2 = x1.cast<double>();
x_2(2) = 1.0; //FIXME: Bad Hack
tf_12 = transformation.inverse().eval();
nan1 = false;
nan2 = true;
}*/
Eigen::Vector3d mu_1 = x_1.head<3>();
Eigen::Vector3d mu_2 = x_2.head<3>();
Eigen::Vector3d mu_1_in_frame_2 = (tf_12 * x_1).head<3>(); // μ₁⁽²⁾ = T₁₂ μ₁⁽¹⁾
//New Shortcut to determine clear outliers
if(use_error_shortcut)
{
double delta_sq_norm = (mu_1_in_frame_2 - mu_2).squaredNorm();
double sigma_max_1 = std::max(raster_cov_x, depth_covariance(mu_1(2)));//Assuming raster_cov_x and _y to be approx. equal
double sigma_max_2 = std::max(raster_cov_x, depth_covariance(mu_2(2)));//Assuming raster_cov_x and _y to be approx. equal
if(delta_sq_norm > 2.0 * (sigma_max_1+sigma_max_2)) //FIXME: Factor 3 for mahal dist should be gotten from caller
{
return std::numeric_limits<double>::max();
}
}
Eigen::Matrix3d rotation_mat = tf_12.block(0,0,3,3);
//Point 1
Eigen::Matrix3d cov1 = Eigen::Matrix3d::Zero();
cov1(0,0) = 1 * raster_cov_x * mu_1(2); //how big is 1px std dev in meter, depends on depth
cov1(1,1) = 1 * raster_cov_y * mu_1(2); //how big is 1px std dev in meter, depends on depth
if(nan1) cov1(2,2) = 1e9; //stddev for unknown: should be within 100m
else cov1(2,2) = depth_covariance(mu_1(2));
//Point2
Eigen::Matrix3d cov2 = Eigen::Matrix3d::Zero();
cov2(0,0) = 1 * raster_cov_x* mu_2(2); //how big is 1px std dev in meter, depends on depth
cov2(1,1) = 1 * raster_cov_y* mu_2(2); //how big is 1px std dev in meter, depends on depth
if(nan2) cov2(2,2) = 1e9; //stddev for unknown: should be within 100m
else cov2(2,2) = depth_covariance(mu_2(2));
Eigen::Matrix3d cov1_in_frame_2 = rotation_mat.transpose() * cov1 * rotation_mat;//Works since the cov is diagonal => Eig-Vec-Matrix is Identity
// Δμ⁽²⁾ = μ₁⁽²⁾ - μ₂⁽²⁾
Eigen::Vector3d delta_mu_in_frame_2 = mu_1_in_frame_2 - mu_2;
delta_mu_in_frame_2(2) = isnan(delta_mu_in_frame_2(2)) ? 0.0 : delta_mu_in_frame_2(2);//FIXME: Hack: set depth error to 0 if NaN
// Σc = (Σ₁ + Σ₂)
Eigen::Matrix3d cov_mat_sum_in_frame_2 = cov1_in_frame_2 + cov2;
//ΔμT Σc⁻¹Δμ
//double sqrd_mahalanobis_distance = delta_mu_in_frame_2.transpose() * cov_mat_sum_in_frame_2.inverse() * delta_mu_in_frame_2;
double sqrd_mahalanobis_distance = delta_mu_in_frame_2.transpose() *cov_mat_sum_in_frame_2.ldlt().solve(delta_mu_in_frame_2);
if(!(sqrd_mahalanobis_distance >= 0.0))
{
return std::numeric_limits<double>::max();
}
return sqrd_mahalanobis_distance;
}
float getMinDepthInNeighborhood(const cv::Mat& depth, cv::Point2f center, float diameter){
// Get neighbourhood area of keypoint
int radius = (diameter - 1)/2;
int top = center.y - radius; top = top < 0 ? 0 : top;
int left = center.x - radius; left = left < 0 ? 0 : left;
int bot = center.y + radius; bot = bot > depth.rows ? depth.rows : bot;
int right = center.x + radius; right = right > depth.cols ? depth.cols : right;
cv::Mat neigborhood(depth, cv::Range(top, bot), cv::Range(left,right));
double minZ = std::numeric_limits<float>::quiet_NaN();
cv::minMaxLoc(neigborhood, &minZ);
if(minZ == 0.0){ //FIXME: Why are there features with depth set to zero?
ROS_INFO_THROTTLE(1,"Caught feature with zero in depth neighbourhood");
minZ = std::numeric_limits<float>::quiet_NaN();
}
return static_cast<float>(minZ);
}
//#include "parameter_server.h" //For pointcloud definitions
#include <pcl/ros/conversions.h>
//#include <pcl_ros/transforms.h>
//#include <Eigen/Core>
#include <math.h>
#define SQRT_2_PI 2.5066283
#define SQRT_2 1.41421
#define LOG_SQRT_2_PI = 0.9189385332
inline int round(float d)
{
return static_cast<int>(floor(d + 0.5));
}
// Returns the probability of [-inf,x] of a gaussian distribution
double cdf(double x, double mu, double sigma)
{
return 0.5 * (1 + erf((x - mu) / (sigma * SQRT_2)));
}
void observationLikelihood(const Eigen::Matrix4f& proposed_transformation,//new to old
pointcloud_type::Ptr new_pc,
pointcloud_type::Ptr old_pc,
double& likelihood,
double& confidence,
unsigned int& inliers,
unsigned int& outliers,
unsigned int& occluded,
unsigned int& all)
{
ScopedTimer s(__FUNCTION__);
int skip_step = ParameterServer::instance()->get<int>("emm__skip_step");
bool mark_outliers = ParameterServer::instance()->get<bool>("emm__mark_outliers");
double observability_threshold = ParameterServer::instance()->get<double>("observability_threshold");
inliers = outliers = occluded = all = 0;
if(skip_step < 0 || observability_threshold <= 0.0){
inliers = all = 1;
return;
}
if(old_pc->width <= 1 || old_pc->height <= 1){
//We need structured point clouds
ROS_ERROR("Point Cloud seems to be non-structured: %u/%u (w/h). Observation can not be evaluated! ", old_pc->width, old_pc->height);
if(ParameterServer::instance()->get<double>("voxelfilter_size") > 0){
ROS_ERROR("The parameter voxelfilter_size is set. This is incompatible with the environment measurement model (parameter 'observability_threshold')");
}
inliers = all = 1;
return;
}
pointcloud_type new_pc_transformed;
pcl::transformPointCloud(*new_pc, new_pc_transformed, proposed_transformation);
//Camera Calibration FIXME: Get actual values from cameraInfo (need to store in node?)
ParameterServer* ps = ParameterServer::instance();
float cx = ps->get<double>("depth_camera_cx") > 0 ? ps->get<double>("depth_camera_cx") / (640.0/old_pc->width) : old_pc->width /2 - 0.5;
float cy = ps->get<double>("depth_camera_cy") > 0 ? ps->get<double>("depth_camera_cy") / (480.0/old_pc->height) : old_pc->height/2 - 0.5;
float fx = ps->get<double>("depth_camera_fx") > 0 ? ps->get<double>("depth_camera_fx") : 525;
float fy = ps->get<double>("depth_camera_fy") > 0 ? ps->get<double>("depth_camera_fy") : 525;
fx = fx / (640.0/old_pc->width);
fy = fy / (480.0/old_pc->height);
double sumloglikelihood = 0.0;
double observation_count = 0.0;
unsigned int bad_points = 0, good_points = 0, occluded_points = 0;
#pragma omp parallel for reduction(+: good_points, bad_points, occluded_points)
for(int new_ry = 0; new_ry < (int)new_pc->height; new_ry+=skip_step){
for(int new_rx = 0; new_rx < (int)new_pc->width; new_rx+=skip_step, all++){
//Backproject transformed new 3D point to 2d raster of old image
//TODO: Cache this?
point_type& p = new_pc_transformed.at(new_rx, new_ry);
if(p.z != p.z) continue; //NaN
if(p.z < 0) continue; // Behind the camera
int old_rx_center = round((p.x / p.z)* fx + cx);
int old_ry_center = round((p.y / p.z)* fy + cy);
if(old_rx_center >= (int)old_pc->width || old_rx_center < 0 ||
old_ry_center >= (int)old_pc->height|| old_ry_center < 0 )
{
ROS_DEBUG("New point not projected into old image, skipping");
continue;
}
int nbhd = 2; //1 => 3x3 neighbourhood
bool good_point = false, occluded_point = false, bad_point = false;
int startx = std::max(0,old_rx_center - nbhd);
int starty = std::max(0,old_ry_center - nbhd);
int endx = std::min(static_cast<int>(old_pc->width), old_rx_center + nbhd +1);
int endy = std::min(static_cast<int>(old_pc->height), old_ry_center + nbhd +1);
int neighbourhood_step = 2; //Search for depth jumps in this area
for(int old_ry = starty; old_ry < endy; old_ry+=neighbourhood_step){
for(int old_rx = startx; old_rx < endx; old_rx+=neighbourhood_step){
const point_type& old_p = old_pc->at(old_rx, old_ry);
if(old_p.z != old_p.z) continue; //NaN
//ROS_INFO("Msrmnt. P1: (%f;%f;%f) P2: (%f;%f;%f)", p.x, p.y, p.z, old_p.x, old_p.y, old_p.z);
//Sensor model
//double dz = (old_p.z - p.z);//Positive: behind old_z
// likelihood for old msrmnt = new msrmnt:
double old_sigma = depth_covariance(old_p.z);
//TODO: (Wrong) Assumption: Transformation does not change the viewing angle.
double new_sigma = depth_covariance(p.z);
//Assumption: independence of sensor noise lets us sum variances
double joint_sigma = old_sigma + new_sigma;
///TODO: Compute correctly transformed new sigma in old_z direction
//Gaussian probability of new being same as old
//double mahal_dist = -0.5*(dz*dz) / joint_sigma;
//double observation_p = 1.0/(SQRT_2_PI * sqrt(joint_sigma)) * exp(mahal_dist);
//Cumulative of position: probability of being occluded