Namespaces |
| namespace | plugins |
| | Dynamically loaded plugins namespace.
|
Classes |
| class | AlvarException |
| | ALVAR exception class. More...
|
| struct | AlvarLoader |
| class | Bitset |
| | Bitset is a basic class for handling bit sequences More...
|
| class | BitsetExt |
| | An extended Bitset ( BitsetExt ) for handling e.g. Hamming encoding/decoding. More...
|
| class | Camera |
| | Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camera. More...
|
| class | CameraEC |
| | Version of Camera using external container. More...
|
| class | CameraMoves |
| class | Capture |
| | Capture interface that plugins must implement. More...
|
| class | CaptureDevice |
| | CaptureDevice holder for camera information. More...
|
| class | CaptureFactory |
| | CaptureFactory for creating Capture classes. More...
|
| class | CaptureFactoryPrivate |
| class | CapturePlugin |
| | CapturePlugin interface that plugins must implement. More...
|
| class | Container3d |
| | Generic container to store any information in 3D (features, photos, ...) More...
|
| class | Container3dLimitDist |
| | Functor class for Container3d Limit() to limit the search space with distance. More...
|
| class | Container3dSortDist |
| | Functor class for Container3d Sort() to sort the search base using distance to specified origin. More...
|
| class | Container3dSortSize |
| | Functor class for Container3d Sort() to sort the search base using content size. More...
|
| class | DirectoryIterator |
| | DirectoryIterator for iterating over files and directories. More...
|
| class | DirectoryIteratorPrivate |
| class | DirectoryIteratorPrivateData |
| class | DoEraseTest |
| | This is default functor for testing which items in the container should be erased. More...
|
| class | DoHandleTest |
| | This is a default functor for testing which items in the container should be handled by each method. More...
|
| class | ExternalContainer |
| | Basic structure to be usable with EC methods. More...
|
| class | FernClassifierWrapper |
| | FernClassifier subclass that implements binary reading and writting. More...
|
| class | FernImageDetector |
| | Image detector based on a Fern classifier. More...
|
| class | FernPoseEstimator |
| | Pose estimation class for FernImageDetector. More...
|
| class | FileFormatUtils |
| | Utility functions for file reading / writing. More...
|
| class | Filter |
| | Filter is pure virtual class describing the basic virtual interface for all filters More...
|
| class | FilterArray |
| | Class for handling an array of filtered values. More...
|
| class | FilterAverage |
| | FilterAverage provides an average filter More...
|
| class | FilterDoubleExponentialSmoothing |
| | FilterDoubleExponentialSmoothing provides an weighted running average filter More...
|
| class | FilterMedian |
| | FilterMedian provides an median filter More...
|
| class | FilterRunningAverage |
| | FilterRunningAverage provides an weighted running average filter More...
|
| class | Histogram |
| | Class for N-dimensional Histograms. More...
|
| class | HistogramSubpixel |
| | N-dimensional Histograms calculating also the subpixel average for max bin. More...
|
| struct | Homography |
| | Simple Homography class for finding and projecting points between two planes. More...
|
| struct | Index |
| | Class for N-dimensional index to be used e.g. with STL maps. More...
|
| class | IndexRansac |
| | Implementation of a general RANdom SAmple Consensus algorithm with implicit parameters. More...
|
| class | IntegralGradient |
| | IntegralGradient is used for calculating rectangular image gradients rapidly More...
|
| class | IntegralImage |
| | IntegralImage is used for calculating rectangular image sums and averages rapidly More...
|
| class | IntIndex |
| | Class for calculating "evenly spaced" integer indices for data sequence. More...
|
| class | Kalman |
| | Kalman implementation. More...
|
| class | KalmanCore |
| | Core implementation for Kalman. More...
|
| class | KalmanEkf |
| | Extended Kalman Filter (EKF) implementation. More...
|
| class | KalmanSensor |
| | Kalman sensor implementation. More...
|
| class | KalmanSensorCore |
| | Core implementation for Kalman sensor. More...
|
| class | KalmanSensorEkf |
| | Extended Kalman Filter (EKF) sensor implementation. More...
|
| class | KalmanVisualize |
| | Class for visualizing Kalman filter. More...
|
| class | Labeling |
| | Base class for labeling connected components from binary image. More...
|
| class | LabelingCvSeq |
| | Labeling class that uses OpenCV routines to find connected components. More...
|
| struct | Line |
| | Struct representing a line. The line is parametrized by its center and direction vector. More...
|
| class | Lock |
| | Lock for simplifying mutex handling. More...
|
| class | Marker |
| | Basic 2D Marker functionality. More...
|
| class | MarkerArtoolkit |
| | MarkerArtoolkit for using matrix markers similar with the ones used in ARToolkit. More...
|
| class | MarkerData |
| | MarkerData contains matrix of Hamming encoded data. More...
|
| class | MarkerDetector |
| | MarkerDetector for detecting markers of type M More...
|
| class | MarkerDetectorEC |
| | Version of MarkerDetector using external container. More...
|
| class | MarkerDetectorImpl |
| | Templateless version of MarkerDetector. Please use MarkerDetector instead. More...
|
| class | MarkerIterator |
| | Iterator type for traversing templated Marker vector without the template. More...
|
| class | MarkerIteratorImpl |
| | Iterator implementation for traversing templated Marker vector without the template. More...
|
| class | MultiMarker |
| | Base class for using MultiMarker. More...
|
| class | MultiMarkerBundle |
| | Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud). More...
|
| class | MultiMarkerEC |
| | Version of MultiMarker using external container. More...
|
| class | MultiMarkerFiltered |
| | Multi marker that is constructed by first calculating the marker poses directly relative to base marker and then filtering the results using e.g. median filter. More...
|
| class | MultiMarkerInitializer |
| | Initializes multi marker by estimating their relative positions from one or more images. More...
|
| class | Mutex |
| | Mutex for synchronizing multiple threads. More...
|
| class | MutexPrivate |
| class | MutexPrivateData |
| class | Optimization |
| | Non-linear optimization routines. There are three methods implemented that include Gauss-Newton, Levenberg-Marquardt and Tukey m-estimator. More...
|
| class | Plugin |
| | Plugin for loading dynamic libraries. More...
|
| class | PluginPrivate |
| class | PluginPrivateData |
| struct | Point |
| | Simple Point class meant to be inherited from OpenCV point-classes. For example: Point<CvPoint2D64f> p. More...
|
| class | Pose |
| | Pose representation derived from the Rotation class More...
|
| struct | ProjectParams |
| struct | ProjPoints |
| | Simple structure for collecting 2D and 3D points e.g. for camera calibration. More...
|
| class | Ransac |
| | Implementation of a general RANdom SAmple Consensus algorithm. More...
|
| class | RansacImpl |
| | Internal implementation of RANSAC. Please use Ransac or IndexRansac. More...
|
| class | Rotation |
| | Rotation structure and transformations between different parameterizations. More...
|
| class | Serialization |
| | Class for serializing class content to/from file or std::iostream. More...
|
| struct | SerializationFormatterXml |
| class | SimpleSfM |
| | Simple structure from motion implementation using CameraEC , MarkerDetectorEC and TrackerFeaturesEC. More...
|
| struct | StartThreadParameters |
| class | Threads |
| | Threads vector for handling multiple threads. More...
|
| class | ThreadsPrivate |
| class | ThreadsPrivateData |
| class | Timer |
| | Timer for measuring execution time. More...
|
| class | TimerPrivate |
| class | TimerPrivateData |
| class | Tracker |
| | Pure virtual base class for tracking optical flow. More...
|
| class | TrackerFeatures |
| | TrackerFeatures tracks features using OpenCV's cvGoodFeaturesToTrack and cvCalcOpticalFlowPyrLK More...
|
| class | TrackerFeaturesEC |
| | Version of TrackerFeatures using external container. More...
|
| class | TrackerOrientation |
| | Track orientation based only on features in the image plane. More...
|
| class | TrackerPsa |
| | TrackerPsa implements a very simple PSA tracker More...
|
| class | TrackerPsaRot |
| | TrackerPsaRot implements a slightly extended version of a TrackerPsa which can also detect sideways rotation More...
|
| class | TrackerStat |
| | TrackerStat deduces the optical flow based on tracked features using Seppo Valli's statistical tracking. More...
|
| class | TrackerStatRot |
| | TrackerStatRot implements a slightly extended version of TrackerStat which can also detect sideways rotation. More...
|
| class | TrifocalTensor |
| | Trifocal tensor works for three images like a fundamental matrix works for two images. More...
|
| class | Uncopyable |
| | Uncopyable for preventing object copies. More...
|
| class | UnscentedKalman |
| | Implementation of unscented kalman filter (UKF) for filtering non-linear processes. More...
|
| class | UnscentedObservation |
| | Observation model for an unscented kalman filter. More...
|
| class | UnscentedProcess |
| | Process model for an unscented kalman filter. More...
|
Typedefs |
typedef ALVAR_EXPORT Point
< CvPoint2D64f > | PointDouble |
| | The default double point type.
|
typedef ALVAR_EXPORT Point
< CvPoint > | PointInt |
| | The default integer point type.
|
Enumerations |
| enum | FILE_FORMAT { FILE_FORMAT_DEFAULT,
FILE_FORMAT_OPENCV,
FILE_FORMAT_TEXT,
FILE_FORMAT_XML
} |
Functions |
| template<class T > |
| T | absdiff (T c1, T c2) |
| void | alvarInfo () |
| double ALVAR_EXPORT | angle (CvPoint *A, CvPoint *B, CvPoint *C, CvPoint *D, int isDirectionDependent) |
| | Computes the angle between lines AB and CD.
|
| void ALVAR_EXPORT | BuildHideTexture (IplImage *image, IplImage *hide_texture, Camera *cam, double gl_modelview[16], PointDouble topleft, PointDouble botright) |
| | This function is used to construct a texture image which is needed to hide a marker from the original video frame. See SampleMarkerHide.cpp for example implementation.
|
| void | CreateShadowPoint (CvPoint3D32f &p3d_sh, CvPoint3D32f p3d, CameraEC *cam, Pose *camera_pose, float parallax_length, float triangulate_angle) |
| int ALVAR_EXPORT | cross (CvPoint *A, CvPoint *B, CvPoint *C) |
| | Computes the cross product AB x AC.
|
| template<class C > |
| double ALVAR_EXPORT | Deg2Rad (const C &v) |
| | Converts an angle from degrees to radians.
|
| double | det (double *r0, double *r1, double *r2, double *r3) |
| template<class C > |
| int ALVAR_EXPORT | diff (const std::vector< C > &v, std::vector< C > &ret) |
| | Calculates the difference between the consecutive vector elements.
|
| double ALVAR_EXPORT | distance (CvPoint *A, CvPoint *B) |
| | Compute the distance from A to B.
|
| int ALVAR_EXPORT | dot (CvPoint *A, CvPoint *B, CvPoint *C) |
| | Computes dot product AB.BC.
|
| template<class PointType > |
| void | DrawBB (IplImage *image, const std::vector< PointType > &points, CvScalar color, std::string label="") |
| | Draws the bounding box of a connected component (Blob).
|
| void ALVAR_EXPORT | DrawCircles (IplImage *image, const CvSeq *contour, int radius, CvScalar color=CV_RGB(255, 0, 0)) |
| | Draws circles to the contour points that are obtained by Labeling class.
|
| void ALVAR_EXPORT | DrawCVEllipse (IplImage *image, CvBox2D &ellipse, CvScalar color, bool fill=false, double par=0) |
| | Draws OpenCV ellipse.
|
| void ALVAR_EXPORT | DrawLine (IplImage *image, const Line line, CvScalar color=CV_RGB(0, 255, 0)) |
| | Draws a line.
|
| template<class PointType > |
| void | DrawLines (IplImage *image, const std::vector< PointType > &points, CvScalar color, bool loop=true) |
| | Draws lines between consecutive points stored in vector (polyline).
|
| void ALVAR_EXPORT | DrawLines (IplImage *image, const CvSeq *contour, CvScalar color=CV_RGB(255, 0, 0)) |
| | Draws lines between consecutive contour points.
|
| void | DrawPoints (IplImage *image, const vector< CvPoint > &points, CvScalar color) |
| void ALVAR_EXPORT | DrawPoints (IplImage *image, const std::vector< CvPoint > &points, CvScalar color) |
| | Draws a set of points.
|
| void ALVAR_EXPORT | DrawPoints (IplImage *image, const CvSeq *contour, CvScalar color=CV_RGB(255, 0, 0)) |
| | Draws points of the contour that is obtained by Labeling class.
|
| template<class PointType > |
| void | DrawPoints (IplImage *image, const std::vector< PointType > &points, CvScalar color, int radius=1) |
| | Draws circles to the array of points.
|
| void ALVAR_EXPORT | DrawTexture (IplImage *image, IplImage *texture, Camera *cam, double gl_modelview[16], PointDouble topleft, PointDouble botright) |
| | Draws the texture generated by BuildHideTexture to given video frame. For better performance, use OpenGL instead. See SampleMarkerHide.cpp for example implementation.
|
| template<typename T , typename F > |
| int | EraseItemsEC (std::map< int, T > &container, F do_erase_test) |
| | Erasing items from container using DoEraseTest type functor.
|
| void ALVAR_EXPORT | errorAtLine (int status, int error, const char *filename, unsigned int line, const char *format,...) |
| | Error reporting function inspired by error_at_line() on Linux.
|
| void | Est (CvMat *state, CvMat *estimation, void *param) |
| int | exp_filt2 (vector< double > &v, vector< double > &ret, bool clamp) |
| int ALVAR_EXPORT | exp_filt2 (std::vector< double > &v, std::vector< double > &ret, bool clamp) |
| int | find_zero_crossings (const vector< double > &v, vector< int > &corners, int offs) |
| int ALVAR_EXPORT | find_zero_crossings (const std::vector< double > &v, std::vector< int > &corners, int offs=20) |
| | Finds zero crossings of given vector elements (sequence).
|
| void | FitCVEllipse (const vector< PointDouble > &points, CvBox2D &ellipse_box) |
| void ALVAR_EXPORT | FitCVEllipse (const std::vector< PointDouble > &points, CvBox2D &ellipse_box) |
| | Uses OpenCV routine to fit ellipse to a vector of points.
|
| void | FitLineGray (CvMat *line_data, float params[4], IplImage *gray) |
| void | FitLines (vector< Line > &lines) |
| int | FitLines (vector< Line > &lines, const vector< int > &corners, const vector< PointInt > &edge, IplImage *grey) |
| int ALVAR_EXPORT | FitLines (std::vector< Line > &lines, const std::vector< int > &corners, const std::vector< PointInt > &edge, IplImage *grey=0) |
| | Fit lines to vector of points.
|
| void | GetOrigo (Pose *pose, CvMat *O) |
| void | GetPointOnLine (const Pose *pose, Camera *camera, const CvPoint2D32f *u, CvMat *P) |
| double * | getRow (double *m, int row) |
| PointDouble ALVAR_EXPORT | Intersection (const Line &l1, const Line &l2) |
| | Calculates an intersection point of two lines.
|
| double ALVAR_EXPORT | Limit (double val, double min_val, double max_val) |
| | Limits a number to between two values.
|
| double ALVAR_EXPORT | linePointDist (CvPoint *A, CvPoint *B, CvPoint *C, bool isSegment) |
| | Computes the distance from point C to line (segment) AB.
|
| int | MarkerIdToContainerId (int marker_id, int corner_id, int first_id=0, int last_id=65535) |
| | Calculate the index used in external container map for specified marker_id.
|
| bool | MidPointAlgorithm (CvMat *o1, CvMat *o2, CvMat *p1, CvMat *p2, CvPoint3D32f &X, double limit) |
| Rotation | operator+ (const Rotation &r1, const Rotation &r2) |
| void ALVAR_EXPORT | out_matrix (const CvMat *m, const char *name) |
| | Output OpenCV matrix for debug purposes.
|
| template<class PointType > |
| double | PointSquaredDistance (PointType p1, PointType p2) |
| | Returns the squared distance of two points.
|
| float | PointVectorFromCamera (CvPoint3D32f p3d, CvPoint3D32f &p3d_vec, Pose *camera_pose) |
| double ALVAR_EXPORT | polyLinePointDist (CvPoint *PointList, int nPnts, CvPoint *C, int *index, int isClosedPolygon) |
| | Calculates minimum distance from Point C to Polygon whose points are in list PointList.
|
| static void | Project (CvMat *state, CvMat *projection, void *x) |
| static void | ProjectRot (CvMat *state, CvMat *projection, void *x) |
| template<class C > |
| double ALVAR_EXPORT | Rad2Deg (const C &v) |
| | Converts an angle from radians to degrees.
|
| int | round (double x) |
| template<class C > |
| int ALVAR_EXPORT | Sign (const C &v) |
| | Returns the sign of a number.
|
| void ALVAR_EXPORT | sleep (unsigned long milliseconds) |
| | Sleep for a specified amount of milliseconds.
|
| static DWORD WINAPI | startThread (void *parameters) |
| void | STRCPY (char *to, size_t size, const char *src) |
Variables |
| static const char * | ALVAR_DATE = "2012-06-20" |
| | Date the library was built.
|
| static const char * | ALVAR_SYSTEM = "Linux 3.2.0-24-generic x86_64" |
| | System the library was built on.
|
| static const char * | ALVAR_VERSION = "2.0.0" |
| | Entire version string.
|
| static const int | ALVAR_VERSION_MAJOR = 2 |
| | Major version number.
|
| static const int | ALVAR_VERSION_MINOR = 0 |
| | Minor version number.
|
| static const char * | ALVAR_VERSION_NODOTS = "200" |
| | Entire version string without dots.
|
| static const int | ALVAR_VERSION_PATCH = 0 |
| | Patch version number.
|
| static const char * | ALVAR_VERSION_REVISION = "" |
| | Revision version string.
|
| static const char * | ALVAR_VERSION_TAG = "" |
| | Tag version string.
|
| struct alvar::AlvarLoader | alvarBasicLoader |
| Camera * | camera |
| CameraMoves | moving |
| int | n_images |
| int | n_markers |
| const double | PI = 3.14159265 |