| Public Member Functions | |
| double | compareSURFDescriptors (const float *d1, const float *d2, double best, int length) | 
| Error_Prop () | |
| void | findPairs (const CvSeq *objectKeypoints, const CvSeq *objectDescriptors, const CvSeq *imageKeypoints, const CvSeq *imageDescriptors, vector< int > &ptpairs) | 
| void | flannFindPairs (const CvSeq *, const CvSeq *objectDescriptors, const CvSeq *, const CvSeq *imageDescriptors, vector< int > &ptpairs) | 
| void | imageCb_l (const sensor_msgs::ImageConstPtr &msg) | 
| void | imageCb_r (const sensor_msgs::ImageConstPtr &msg) | 
| void | init () | 
| int | locatePlanarObject (const CvSeq *objectKeypoints, const CvSeq *objectDescriptors, const CvSeq *imageKeypoints, const CvSeq *imageDescriptors, const CvPoint src_corners[4], CvPoint dst_corners[4]) | 
| int | naiveNearestNeighbor (const float *vec, int laplacian, const CvSeq *model_keypoints, const CvSeq *model_descriptors) | 
| void | run () | 
| void | VO_3D_to_matches () | 
| void | VO_clean () | 
| void | VO_cloudFilter () | 
| void | VO_ConsecutiveMatching () | 
| void | VO_get_RT_RANSAC () | 
| void | VO_matches_to_3D () | 
| void | VO_matchFilter () | 
| void | VO_RT_to_world () | 
| void | VO_StereoMatching () | 
| void | VO_ViewAll () | 
| void | VO_ViewConsecutive () | 
| void | VO_ViewStereo () | 
| void | ypr (const Matrix< float, 3, 3 > Rot, Matrix< float, 3, 1 > &ypr_) | 
| ~Error_Prop () | |
| Public Attributes | |
| float | alfa [4] | 
| float | alfa_l [2] | 
| float | alfa_r [2] | 
| float | alfa_U_l | 
| float | alfa_U_r | 
| float | alfa_V_l | 
| float | alfa_V_r | 
| Eigen::Matrix< float, 3, 3 > | cam2world | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_a | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_ant | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_b | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_c | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_odom | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_odom2 | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_pos | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_t | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_w | 
| pcl::PointCloud< pcl::PointXYZ > | cloud_wRT | 
| CvMat | Cov | 
| pcl::PointCloud< pcl::PointXYZ > | cpts1 | 
| pcl::PointCloud< pcl::PointXYZ > | cpts1RANSAC | 
| pcl::PointCloud< pcl::PointXYZ > | cpts_ant | 
| ros::Time | current_time | 
| CvMat | d2C_dydx | 
| Quaterniond | fq | 
| Mat | H_l2r | 
| Eigen::Matrix< float, 4, 4 > | H_l2r_ | 
| float | h_r [16] | 
| CvMat | H_r | 
| CvMat | HC | 
| CvMat | Hcam2rob | 
| double | hcam2rob [16] | 
| Eigen::Matrix< float, 4, 4 > | Hcam2rob_ | 
| CvMat * | Hcaminv | 
| Mat | im1 | 
| Mat | im2 | 
| vector< int > | indices_a | 
| vector< int > | indices_b | 
| double | inv_cam2rob [16] | 
| CvMat | invC2R | 
| CvMat | Jf | 
| Eigen::Matrix< float, 3, 4 > | Jf_ | 
| ros::Time | last_time | 
| IplImage * | left_ | 
| IplImage * | left_1 | 
| IplImage * | left_ant | 
| IplImage * | left_gray | 
| IplImage * | left_gray_ant | 
| CvSeq * | leftDescriptors1 | 
| CvSeq * | leftDescriptors2 | 
| CvSeq * | leftDescriptors3 | 
| CvSeq * | leftKeypoints1 | 
| CvSeq * | leftKeypoints2 | 
| CvSeq * | leftKeypoints3 | 
| float | mean [3] | 
| float | meanul | 
| float | meanur | 
| float | meanvl | 
| float | meanvr | 
| int | Nclouds | 
| int | ncol | 
| int | Npoints | 
| int | nrow | 
| Eigen::Matrix< float, 3, 500 > | nube1 | 
| Eigen::Matrix< float, 3, 500 > | nube2 | 
| int | numRandPoints | 
| geometry_msgs::Pose | odom3D | 
| Matrix< float, 3, 1 > | odom_1 | 
| Matrix< float, 3, 1 > | odom_2 | 
| float | om [3] | 
| CvMat | p_xyz | 
| Eigen::Matrix< float, 3, 2000 > | Points3D | 
| vector< int > | ptpairs1 | 
| vector< int > | ptpairs1_resp | 
| vector< int > | ptpairs2 | 
| vector< int > | ptpairs2_resp | 
| vector< int > | ptpairs3 | 
| vector< int > | ptpairs3_resp | 
| float | px | 
| float | py | 
| float | pz | 
| tf::Quaternion | quat_ant | 
| Mat | R | 
| Eigen::Matrix3f | R_ | 
| Mat | randomUL | 
| Mat | randomUR | 
| Mat | randomVL | 
| Mat | randomVR | 
| Mat | randomx | 
| Mat | randomy | 
| Mat | randomz | 
| Mat | rdm | 
| IplImage * | right_ | 
| IplImage * | right_1 | 
| IplImage * | right_gray | 
| CvSeq * | rightDescriptors1 | 
| CvSeq * | rightDescriptors2 | 
| CvSeq * | rightDescriptors3 | 
| CvSeq * | rightKeypoints1 | 
| CvSeq * | rightKeypoints2 | 
| CvSeq * | rightKeypoints3 | 
| Matrix< float, 3, 3 > | Rot_12 | 
| Matrix< float, 3, 3 > | Rot_i | 
| CvMat | RTCamFr | 
| int | sigma_ul | 
| int | sigma_ur | 
| int | sigma_vl | 
| int | sigma_vr | 
| int | size | 
| bool | START | 
| float | T [3] | 
| double | t_stereo | 
| double | th | 
| Vector4d | trans_ | 
| Eigen::Matrix4f | transformation | 
| Matrix< float, 3, 1 > | Tras_12 | 
| Matrix< float, 3, 1 > | Tras_i | 
| float | tx | 
| float | ty | 
| float | tz | 
| float | uol | 
| float | uor | 
| pcl::PointCloud< pcl::PointXYZ > | UV_l | 
| pcl::PointCloud< pcl::PointXYZ > | UV_r | 
| CvMat | uvs_l | 
| CvMat | uvs_r | 
| float | vol | 
| float | vor | 
| double | vth | 
| double | vx | 
| double | vy | 
| pcl::PointCloud< pcl::PointXYZ > | wpts1 | 
| pcl::PointCloud< pcl::PointXYZ > | wpts1RANSAC | 
| pcl::PointCloud< pcl::PointXYZ > | wpts1RT | 
| float | wpx_ | 
| Mat | wpxyz | 
| float | wpy_ | 
| float | wpz_ | 
| double | x | 
| float | xl [2] | 
| float | xlims [2] | 
| double | y | 
| float | yl [2] | 
| float | ylims [2] | 
| double | z | 
| float | zl [2] | 
| float | zlims [2] | 
| Private Attributes | |
| image_transport::Subscriber | image_sub_l_ | 
| image_transport::Subscriber | image_sub_r_ | 
| image_transport::ImageTransport | it_ | 
| ros::NodeHandle | n_cpts1 | 
| ros::NodeHandle | n_od | 
| ros::NodeHandle | n_odom | 
| ros::NodeHandle | n_pcl1 | 
| ros::NodeHandle | n_pcl2 | 
| ros::NodeHandle | n_pos | 
| ros::NodeHandle | n_src | 
| ros::NodeHandle | n_src_RT | 
| ros::NodeHandle | n_tgt | 
| ros::NodeHandle | n_wpts1 | 
| ros::NodeHandle | nh_ | 
| tf::TransformBroadcaster | od_broadcaster | 
| CvSURFParams | params | 
| ros::Publisher | pub_cpts1 | 
| ros::Publisher | pub_od | 
| ros::Publisher | pub_odom | 
| ros::Publisher | pub_pcl1 | 
| ros::Publisher | pub_pcl2 | 
| ros::Publisher | pub_pos | 
| ros::Publisher | pub_src | 
| ros::Publisher | pub_src_RT | 
| ros::Publisher | pub_tgt | 
| ros::Publisher | pub_uvl | 
| ros::Publisher | pub_uvr | 
| ros::Publisher | pub_wpts1 | 
| Error_Prop::Error_Prop | ( | ) |  [inline] | 
| Error_Prop::~Error_Prop | ( | ) |  [inline] | 
| double Error_Prop::compareSURFDescriptors | ( | const float * | d1, | 
| const float * | d2, | ||
| double | best, | ||
| int | length | ||
| ) | 
| void Error_Prop::findPairs | ( | const CvSeq * | objectKeypoints, | 
| const CvSeq * | objectDescriptors, | ||
| const CvSeq * | imageKeypoints, | ||
| const CvSeq * | imageDescriptors, | ||
| vector< int > & | ptpairs | ||
| ) | 
| void Error_Prop::flannFindPairs | ( | const CvSeq * | , | 
| const CvSeq * | objectDescriptors, | ||
| const CvSeq * | , | ||
| const CvSeq * | imageDescriptors, | ||
| vector< int > & | ptpairs | ||
| ) | 
| void Error_Prop::imageCb_l | ( | const sensor_msgs::ImageConstPtr & | msg | ) | 
| void Error_Prop::imageCb_r | ( | const sensor_msgs::ImageConstPtr & | msg | ) | 
| void Error_Prop::init | ( | ) | 
| int Error_Prop::locatePlanarObject | ( | const CvSeq * | objectKeypoints, | 
| const CvSeq * | objectDescriptors, | ||
| const CvSeq * | imageKeypoints, | ||
| const CvSeq * | imageDescriptors, | ||
| const CvPoint | src_corners[4], | ||
| CvPoint | dst_corners[4] | ||
| ) | 
| int Error_Prop::naiveNearestNeighbor | ( | const float * | vec, | 
| int | laplacian, | ||
| const CvSeq * | model_keypoints, | ||
| const CvSeq * | model_descriptors | ||
| ) | 
| void Error_Prop::run | ( | void | ) | 
| void Error_Prop::VO_3D_to_matches | ( | ) | 
| void Error_Prop::VO_clean | ( | ) | 
| void Error_Prop::VO_cloudFilter | ( | ) | 
| void Error_Prop::VO_ConsecutiveMatching | ( | ) | 
| void Error_Prop::VO_get_RT_RANSAC | ( | ) | 
| void Error_Prop::VO_matches_to_3D | ( | ) | 
| void Error_Prop::VO_matchFilter | ( | ) | 
| void Error_Prop::VO_RT_to_world | ( | ) | 
| void Error_Prop::VO_StereoMatching | ( | ) | 
| void Error_Prop::VO_ViewAll | ( | ) | 
| void Error_Prop::VO_ViewConsecutive | ( | ) | 
| void Error_Prop::VO_ViewStereo | ( | ) | 
| void Error_Prop::ypr | ( | const Matrix< float, 3, 3 > | Rot, | 
| Matrix< float, 3, 1 > & | ypr_ | ||
| ) | 
| float Error_Prop::alfa[4] | 
| float Error_Prop::alfa_l[2] | 
| float Error_Prop::alfa_r[2] | 
| float Error_Prop::alfa_U_l | 
| float Error_Prop::alfa_U_r | 
| float Error_Prop::alfa_V_l | 
| float Error_Prop::alfa_V_r | 
| Eigen::Matrix<float,3,3> Error_Prop::cam2world | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_a | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_ant | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_b | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_c | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_odom | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_odom2 | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_pos | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_t | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_w | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cloud_wRT | 
| CvMat Error_Prop::Cov | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cpts1 | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cpts1RANSAC | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::cpts_ant | 
| CvMat Error_Prop::d2C_dydx | 
| Quaterniond Error_Prop::fq | 
| Eigen::Matrix<float,4,4> Error_Prop::H_l2r_ | 
| float Error_Prop::h_r[16] | 
| CvMat Error_Prop::H_r | 
| CvMat Error_Prop::HC | 
| CvMat Error_Prop::Hcam2rob | 
| double Error_Prop::hcam2rob[16] | 
| Eigen::Matrix<float,4,4> Error_Prop::Hcam2rob_ | 
| CvMat* Error_Prop::Hcaminv | 
| Mat Error_Prop::im1 | 
| Mat Error_Prop::im2 | 
| double Error_Prop::inv_cam2rob[16] | 
| CvMat Error_Prop::invC2R | 
| CvMat Error_Prop::Jf | 
| Eigen::Matrix<float,3,4> Error_Prop::Jf_ | 
| IplImage* Error_Prop::left_ | 
| IplImage* Error_Prop::left_1 | 
| IplImage* Error_Prop::left_ant | 
| IplImage* Error_Prop::left_gray | 
| IplImage* Error_Prop::left_gray_ant | 
| CvSeq * Error_Prop::leftDescriptors1 | 
| CvSeq * Error_Prop::leftDescriptors2 | 
| CvSeq * Error_Prop::leftDescriptors3 | 
| CvSeq* Error_Prop::leftKeypoints1 | 
| CvSeq * Error_Prop::leftKeypoints2 | 
| CvSeq * Error_Prop::leftKeypoints3 | 
| float Error_Prop::mean[3] | 
| float Error_Prop::meanul | 
| float Error_Prop::meanur | 
| float Error_Prop::meanvl | 
| float Error_Prop::meanvr | 
| ros::NodeHandle Error_Prop::n_cpts1  [private] | 
| ros::NodeHandle Error_Prop::n_od  [private] | 
| ros::NodeHandle Error_Prop::n_odom  [private] | 
| ros::NodeHandle Error_Prop::n_pcl1  [private] | 
| ros::NodeHandle Error_Prop::n_pcl2  [private] | 
| ros::NodeHandle Error_Prop::n_pos  [private] | 
| ros::NodeHandle Error_Prop::n_src  [private] | 
| ros::NodeHandle Error_Prop::n_src_RT  [private] | 
| ros::NodeHandle Error_Prop::n_tgt  [private] | 
| ros::NodeHandle Error_Prop::n_wpts1  [private] | 
| int Error_Prop::ncol | 
| ros::NodeHandle Error_Prop::nh_  [private] | 
| int Error_Prop::nrow | 
| Eigen::Matrix<float,3,500> Error_Prop::nube1 | 
| Eigen::Matrix<float,3,500> Error_Prop::nube2 | 
| Matrix<float,3,1> Error_Prop::odom_1 | 
| Matrix<float,3,1> Error_Prop::odom_2 | 
| float Error_Prop::om[3] | 
| CvMat Error_Prop::p_xyz | 
| CvSURFParams Error_Prop::params  [private] | 
| Eigen::Matrix<float,3,2000> Error_Prop::Points3D | 
| ros::Publisher Error_Prop::pub_cpts1  [private] | 
| ros::Publisher Error_Prop::pub_od  [private] | 
| ros::Publisher Error_Prop::pub_odom  [private] | 
| ros::Publisher Error_Prop::pub_pcl1  [private] | 
| ros::Publisher Error_Prop::pub_pcl2  [private] | 
| ros::Publisher Error_Prop::pub_pos  [private] | 
| ros::Publisher Error_Prop::pub_src  [private] | 
| ros::Publisher Error_Prop::pub_src_RT  [private] | 
| ros::Publisher Error_Prop::pub_tgt  [private] | 
| ros::Publisher Error_Prop::pub_uvl  [private] | 
| ros::Publisher Error_Prop::pub_uvr  [private] | 
| ros::Publisher Error_Prop::pub_wpts1  [private] | 
| float Error_Prop::px | 
| float Error_Prop::py | 
| float Error_Prop::pz | 
| Mat Error_Prop::R | 
| Eigen::Matrix3f Error_Prop::R_ | 
| Mat Error_Prop::rdm | 
| IplImage* Error_Prop::right_ | 
| IplImage* Error_Prop::right_1 | 
| IplImage* Error_Prop::right_gray | 
| CvSeq * Error_Prop::rightDescriptors1 | 
| CvSeq * Error_Prop::rightDescriptors2 | 
| CvSeq * Error_Prop::rightDescriptors3 | 
| CvSeq * Error_Prop::rightKeypoints1 | 
| CvSeq * Error_Prop::rightKeypoints2 | 
| CvSeq * Error_Prop::rightKeypoints3 | 
| Matrix<float,3,3> Error_Prop::Rot_12 | 
| Matrix<float,3,3> Error_Prop::Rot_i | 
| CvMat Error_Prop::RTCamFr | 
| int Error_Prop::size | 
| float Error_Prop::T[3] | 
| double Error_Prop::t_stereo | 
| double Error_Prop::th | 
| Vector4d Error_Prop::trans_ | 
| Eigen::Matrix4f Error_Prop::transformation | 
| Matrix<float,3,1> Error_Prop::Tras_12 | 
| Matrix<float,3,1> Error_Prop::Tras_i | 
| float Error_Prop::tx | 
| float Error_Prop::ty | 
| float Error_Prop::tz | 
| float Error_Prop::uol | 
| float Error_Prop::uor | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::UV_l | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::UV_r | 
| CvMat Error_Prop::uvs_l | 
| CvMat Error_Prop::uvs_r | 
| float Error_Prop::vol | 
| float Error_Prop::vor | 
| double Error_Prop::vth | 
| double Error_Prop::vx | 
| double Error_Prop::vy | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::wpts1 | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::wpts1RANSAC | 
| pcl::PointCloud<pcl::PointXYZ> Error_Prop::wpts1RT | 
| float Error_Prop::wpx_ | 
| float Error_Prop::wpy_ | 
| float Error_Prop::wpz_ | 
| double Error_Prop::x | 
| float Error_Prop::xl[2] | 
| float Error_Prop::xlims[2] | 
| double Error_Prop::y | 
| float Error_Prop::yl[2] | 
| float Error_Prop::ylims[2] | 
| double Error_Prop::z | 
| float Error_Prop::zl[2] | 
| float Error_Prop::zlims[2] |