#include <cstdio>
#include <cv.h>
#include <vector>
#include "one_way_descriptor.h"
#include "one_way_descriptor_base.h"
#include "features.h"
#include "geometric_hash.h"
Go to the source code of this file.
Classes | |
struct | outlet_elem_t |
class | outlet_template_t |
struct | outlet_tuple_t |
Enumerations | |
enum | outlet_color_t { outletWhite = 0, outletOrange = 1 } |
Functions | |
void | calc_bounding_rect (int count, const CvRect *rects, CvRect &bounding_rect) |
void | calc_camera_outlet_pose (CvMat *intrinsic_mat, CvMat *distortion_coeffs, const outlet_template_t &outlet_template, const CvPoint2D32f *image_points, CvMat *rotat, CvMat *translation_vector) |
void | calc_camera_pose (CvMat *intrinsic_mat, CvMat *distortion_coeffs, int point_count, const CvPoint3D32f *object_points, const CvPoint2D32f *image_points, CvMat *rotation_vector, CvMat *translation_vector) |
void | calc_camera_pose_2x1 (CvMat *intrinsic_mat, CvMat *distortion_coeffs, const CvPoint2D32f *centers, CvMat *rotation_vector, CvMat *translation_vector) |
void | calc_camera_pose_2x2 (CvMat *intrinsic_mat, CvMat *distortion_coeffs, const CvPoint2D32f *centers, CvMat *rotation_vector, CvMat *translation_vector) |
CvPoint2D32f | calc_center (CvSeq *seq) |
CvPoint2D32f | calc_center (const std::vector< CvPoint2D32f > &points) |
int | calc_image_homography (IplImage *src, CvMat *map_matrix, CvSize *dst_size, CvPoint2D32f *hor_dir=0, CvPoint3D32f *origin=0, CvPoint2D32f *scale=0, const char *output_path=0, const char *filename=0, CvPoint2D32f *_centers=0) |
void | calc_origin_scale (const CvPoint2D32f *centers, CvMat *map_matrix, CvPoint3D32f *origin, CvPoint2D32f *scale) |
void | calc_outlet_homography (const CvPoint2D32f *centers, CvMat *map_matrix, const outlet_template_t &templ=outlet_template_t(), CvMat *inverse_map_matrix=0) |
void | calc_outlet_homography (const CvPoint2D32f *centers, CvSize src_size, CvMat *map_matrix, CvSize *dst_size) |
CvSeq * | close_seq (CvSeq *seq, CvMemStorage *storage, int closure_dist, IplImage *workspace) |
CvPoint | cvPoint (CvPoint2D32f point) |
int | find_dir (const CvPoint2D32f *dir, int xsign, int ysign) |
int | find_outlet_centroids (IplImage *img, outlet_tuple_t &outlet_tuple, const char *output_path, const char *filename) |
IplImage * | find_templates (IplImage *img, IplImage *templ) |
int | find_tuple (std::vector< outlet_elem_t > &candidates, CvPoint2D32f *centers) |
void | generate_object_points_2x1 (CvPoint3D32f *points) |
void | generate_object_points_2x1 (CvPoint2D32f *points) |
float | length (const CvPoint2D32f &p) |
float | length (const CvPoint3D32f &p) |
void | map_point_homography (CvPoint2D32f point, CvMat *homography, CvPoint2D32f &result) |
void | map_vector_homography (const std::vector< CvPoint2D32f > &points, CvMat *homography, std::vector< CvPoint2D32f > &result) |
CvPoint | operator* (CvPoint pt, float scalar) |
CvPoint2D32f | operator+ (CvPoint2D32f p1, CvPoint2D32f p2) |
CvPoint3D32f | operator+ (CvPoint3D32f p1, CvPoint3D32f p2) |
CvPoint2D32f | operator- (CvPoint2D32f p1, CvPoint2D32f p2) |
CvPoint3D32f | operator- (CvPoint3D32f p1, CvPoint3D32f p2) |
int | order_tuple (CvPoint2D32f *centers) |
int | order_tuple2 (std::vector< outlet_elem_t > &tuple) |
void | readCvPointByName (CvFileStorage *fs, CvFileNode *parent, const char *name, CvPoint &pt) |
void | readTrainingBase (const char *config_filename, char *outlet_filename, char *nonoutlet_filename, std::vector< feature_t > &train_features) |
CvPoint | rect_center (CvRect rect) |
Variables | |
const float | default_hole_contrast = 1.1f |
enum outlet_color_t |
Definition at line 90 of file outlet_tuple.h.
void calc_bounding_rect | ( | int | count, |
const CvRect * | rects, | ||
CvRect & | bounding_rect | ||
) |
Definition at line 519 of file outlet_tuple.cpp.
void calc_camera_outlet_pose | ( | CvMat * | intrinsic_mat, |
CvMat * | distortion_coeffs, | ||
const outlet_template_t & | outlet_template, | ||
const CvPoint2D32f * | image_points, | ||
CvMat * | rotat, | ||
CvMat * | translation_vector | ||
) |
Definition at line 847 of file outlet_tuple.cpp.
void calc_camera_pose | ( | CvMat * | intrinsic_mat, |
CvMat * | distortion_coeffs, | ||
int | point_count, | ||
const CvPoint3D32f * | object_points, | ||
const CvPoint2D32f * | image_points, | ||
CvMat * | rotation_vector, | ||
CvMat * | translation_vector | ||
) |
Definition at line 907 of file outlet_tuple.cpp.
void calc_camera_pose_2x1 | ( | CvMat * | intrinsic_mat, |
CvMat * | distortion_coeffs, | ||
const CvPoint2D32f * | centers, | ||
CvMat * | rotation_vector, | ||
CvMat * | translation_vector | ||
) |
Definition at line 885 of file outlet_tuple.cpp.
void calc_camera_pose_2x2 | ( | CvMat * | intrinsic_mat, |
CvMat * | distortion_coeffs, | ||
const CvPoint2D32f * | centers, | ||
CvMat * | rotation_vector, | ||
CvMat * | translation_vector | ||
) |
Definition at line 894 of file outlet_tuple.cpp.
CvPoint2D32f calc_center | ( | CvSeq * | seq | ) |
Definition at line 32 of file outlet_tuple.cpp.
CvPoint2D32f calc_center | ( | const std::vector< CvPoint2D32f > & | points | ) |
int calc_image_homography | ( | IplImage * | src, |
CvMat * | map_matrix, | ||
CvSize * | dst_size, | ||
CvPoint2D32f * | hor_dir = 0 , |
||
CvPoint3D32f * | origin = 0 , |
||
CvPoint2D32f * | scale = 0 , |
||
const char * | output_path = 0 , |
||
const char * | filename = 0 , |
||
CvPoint2D32f * | _centers = 0 |
||
) |
Definition at line 742 of file outlet_tuple.cpp.
void calc_origin_scale | ( | const CvPoint2D32f * | centers, |
CvMat * | map_matrix, | ||
CvPoint3D32f * | origin, | ||
CvPoint2D32f * | scale | ||
) |
Definition at line 772 of file outlet_tuple.cpp.
void calc_outlet_homography | ( | const CvPoint2D32f * | centers, |
CvMat * | map_matrix, | ||
const outlet_template_t & | templ = outlet_template_t() , |
||
CvMat * | inverse_map_matrix = 0 |
||
) |
Definition at line 592 of file outlet_tuple.cpp.
void calc_outlet_homography | ( | const CvPoint2D32f * | centers, |
CvSize | src_size, | ||
CvMat * | map_matrix, | ||
CvSize * | dst_size | ||
) |
!!!! This is an ugly hack. The real way to do it is to offset homography transform
Definition at line 669 of file outlet_tuple.cpp.
CvSeq* close_seq | ( | CvSeq * | seq, |
CvMemStorage * | storage, | ||
int | closure_dist, | ||
IplImage * | workspace | ||
) |
Definition at line 506 of file outlet_tuple.cpp.
CvPoint cvPoint | ( | CvPoint2D32f | point | ) | [inline] |
Definition at line 27 of file outlet_tuple.h.
int find_dir | ( | const CvPoint2D32f * | dir, |
int | xsign, | ||
int | ysign | ||
) |
Definition at line 61 of file outlet_tuple.cpp.
int find_outlet_centroids | ( | IplImage * | img, |
outlet_tuple_t & | outlet_tuple, | ||
const char * | output_path, | ||
const char * | filename | ||
) |
Definition at line 271 of file outlet_tuple.cpp.
IplImage* find_templates | ( | IplImage * | img, |
IplImage * | templ | ||
) |
Definition at line 810 of file outlet_tuple.cpp.
int find_tuple | ( | std::vector< outlet_elem_t > & | candidates, |
CvPoint2D32f * | centers | ||
) |
void generate_object_points_2x1 | ( | CvPoint3D32f * | points | ) |
Definition at line 861 of file outlet_tuple.cpp.
void generate_object_points_2x1 | ( | CvPoint2D32f * | points | ) |
Definition at line 873 of file outlet_tuple.cpp.
float length | ( | const CvPoint2D32f & | p | ) | [inline] |
Definition at line 57 of file outlet_tuple.h.
float length | ( | const CvPoint3D32f & | p | ) | [inline] |
Definition at line 62 of file outlet_tuple.h.
void map_point_homography | ( | CvPoint2D32f | point, |
CvMat * | homography, | ||
CvPoint2D32f & | result | ||
) |
Definition at line 614 of file outlet_tuple.cpp.
void map_vector_homography | ( | const std::vector< CvPoint2D32f > & | points, |
CvMat * | homography, | ||
std::vector< CvPoint2D32f > & | result | ||
) |
CvPoint operator* | ( | CvPoint | pt, |
float | scalar | ||
) | [inline] |
Definition at line 52 of file outlet_tuple.h.
CvPoint2D32f operator+ | ( | CvPoint2D32f | p1, |
CvPoint2D32f | p2 | ||
) | [inline] |
Definition at line 37 of file outlet_tuple.h.
CvPoint3D32f operator+ | ( | CvPoint3D32f | p1, |
CvPoint3D32f | p2 | ||
) | [inline] |
Definition at line 67 of file outlet_tuple.h.
CvPoint2D32f operator- | ( | CvPoint2D32f | p1, |
CvPoint2D32f | p2 | ||
) | [inline] |
Definition at line 42 of file outlet_tuple.h.
CvPoint3D32f operator- | ( | CvPoint3D32f | p1, |
CvPoint3D32f | p2 | ||
) | [inline] |
Definition at line 47 of file outlet_tuple.h.
int order_tuple | ( | CvPoint2D32f * | centers | ) |
Definition at line 73 of file outlet_tuple.cpp.
int order_tuple2 | ( | std::vector< outlet_elem_t > & | tuple | ) |
void readCvPointByName | ( | CvFileStorage * | fs, |
CvFileNode * | parent, | ||
const char * | name, | ||
CvPoint & | pt | ||
) |
Definition at line 1160 of file outlet_tuple.cpp.
void readTrainingBase | ( | const char * | config_filename, |
char * | outlet_filename, | ||
char * | nonoutlet_filename, | ||
std::vector< feature_t > & | train_features | ||
) |
CvPoint rect_center | ( | CvRect | rect | ) | [inline] |
Definition at line 32 of file outlet_tuple.h.
const float default_hole_contrast = 1.1f |
Definition at line 96 of file outlet_tuple.h.