| alvar::AlvarException | ALVAR exception class |
| alvar::AlvarLoader | |
| ar_track_alvar.msg._AlvarMarker.AlvarMarker | |
| ar_track_alvar::AlvarMarker_< ContainerAllocator > | |
| ar_track_alvar.msg._AlvarMarkers.AlvarMarkers | |
| ar_track_alvar::AlvarMarkers_< ContainerAllocator > | |
| alvar::Bitset | Bitset is a basic class for handling bit sequences |
| alvar::BitsetExt | An extended Bitset ( BitsetExt ) for handling e.g. Hamming encoding/decoding |
| alvar::Camera | Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camera |
| alvar::CameraEC | Version of Camera using external container |
| alvar::CameraMoves | |
| alvar::Capture | Capture interface that plugins must implement |
| alvar::plugins::CaptureCmu | Implementation of Capture interface for Cmu plugin |
| alvar::CaptureDevice | CaptureDevice holder for camera information |
| alvar::plugins::CaptureDSCapture | Implementation of Capture interface for DSCapture plugin |
| alvar::CaptureFactory | CaptureFactory for creating Capture classes |
| alvar::CaptureFactory::CaptureFactoryDestroyer | CaptureFactoryDestroyer for deleting the CaptureFactory singleton |
| alvar::CaptureFactoryPrivate | |
| alvar::plugins::CaptureFile | Implementation of Capture interface for File plugin |
| alvar::plugins::CaptureHighgui | Implementation of Capture interface for Highgui plugin |
| alvar::CapturePlugin | CapturePlugin interface that plugins must implement |
| alvar::plugins::CapturePluginCmu | Implementation of CapturePlugin interface for Cmu plugin |
| alvar::plugins::CapturePluginDSCapture | Implementation of CapturePlugin interface for DSCapture plugin |
| alvar::plugins::CapturePluginFile | Implementation of CapturePlugin interface for File plugin |
| alvar::plugins::CapturePluginHighgui | Implementation of CapturePlugin interface for Highgui plugin |
| alvar::plugins::CapturePluginPtgrey | Implementation of CapturePlugin interface for Ptgrey plugin |
| alvar::plugins::CapturePtgrey | Implementation of Capture interface for Ptgrey plugin |
| alvar::Container3d< T > | Generic container to store any information in 3D (features, photos, ...) |
| alvar::Container3dLimitDist< T > | Functor class for Container3d Limit() to limit the search space with distance |
| alvar::Container3dSortDist< T > | Functor class for Container3d Sort() to sort the search base using distance to specified origin |
| alvar::Container3dSortSize< T > | Functor class for Container3d Sort() to sort the search base using content size |
| CvPoint2D64f | |
| CvTestbed | CvTestbed is a class for making quick OpenCV test applications |
| ros::message_traits::DataType< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::DataType< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| ros::message_traits::Definition< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::Definition< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| alvar::DirectoryIterator | DirectoryIterator for iterating over files and directories |
| alvar::DirectoryIteratorPrivate | |
| alvar::DirectoryIteratorPrivateData | |
| alvar::DoEraseTest< T > | This is default functor for testing which items in the container should be erased |
| alvar::DoHandleTest< T > | This is a default functor for testing which items in the container should be handled by each method |
| Drawable | |
| alvar::ExternalContainer | Basic structure to be usable with EC methods |
| alvar::SimpleSfM::Feature | Extended version of ExternalContainer structure used internally in SimpleSfM |
| alvar::TrackerOrientation::Feature | |
| alvar::FernClassifierWrapper | FernClassifier subclass that implements binary reading and writting |
| alvar::FernImageDetector | Image detector based on a Fern classifier |
| alvar::FernPoseEstimator | Pose estimation class for FernImageDetector |
| alvar::FileFormatUtils | Utility functions for file reading / writing |
| alvar::Filter | Filter is pure virtual class describing the basic virtual interface for all filters |
| alvar::FilterArray< F > | Class for handling an array of filtered values |
| alvar::FilterAverage | FilterAverage provides an average filter |
| alvar::FilterDoubleExponentialSmoothing | FilterDoubleExponentialSmoothing provides an weighted running average filter |
| alvar::FilterMedian | FilterMedian provides an median filter |
| alvar::FilterRunningAverage | FilterRunningAverage provides an weighted running average filter |
| ros::message_traits::HasHeader< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::HasHeader< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| ros::message_traits::HasHeader< const ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::HasHeader< const ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| alvar::Histogram | Class for N-dimensional Histograms |
| alvar::HistogramSubpixel | N-dimensional Histograms calculating also the subpixel average for max bin |
| alvar::Homography | Simple Homography class for finding and projecting points between two planes |
| CvTestbed::Image | Image structure to store the images internally |
| alvar::Index | Class for N-dimensional index to be used e.g. with STL maps |
| alvar::IndexRansac< MODEL > | Implementation of a general RANdom SAmple Consensus algorithm with implicit parameters |
| alvar::IntegralGradient | IntegralGradient is used for calculating rectangular image gradients rapidly |
| alvar::IntegralImage | IntegralImage is used for calculating rectangular image sums and averages rapidly |
| alvar::IntIndex | Class for calculating "evenly spaced" integer indices for data sequence |
| ros::message_traits::IsMessage< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::IsMessage< ::ar_track_alvar::AlvarMarker_< ContainerAllocator >const > | |
| ros::message_traits::IsMessage< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| ros::message_traits::IsMessage< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator >const > | |
| alvar::Container3d< T >::Iterator | Iterator for going through the items in Container3d in the specified order |
| alvar::Kalman | Kalman implementation |
| alvar::KalmanCore | Core implementation for Kalman |
| alvar::KalmanEkf | Extended Kalman Filter (EKF) implementation |
| KalmanOwn | |
| alvar::KalmanSensor | Kalman sensor implementation |
| alvar::KalmanSensorCore | Core implementation for Kalman sensor |
| alvar::KalmanSensorEkf | Extended Kalman Filter (EKF) sensor implementation |
| KalmanSensorOwn | |
| alvar::KalmanVisualize | Class for visualizing Kalman filter |
| alvar::Labeling | Base class for labeling connected components from binary image |
| alvar::LabelingCvSeq | Labeling class that uses OpenCV routines to find connected components |
| alvar::Line | Struct representing a line. The line is parametrized by its center and direction vector |
| alvar::Lock | Lock for simplifying mutex handling |
| alvar::Marker | Basic 2D Marker functionality |
| alvar::MarkerArtoolkit | MarkerArtoolkit for using matrix markers similar with the ones used in ARToolkit |
| alvar::MarkerData | MarkerData contains matrix of Hamming encoded data |
| alvar::MarkerDetector< M > | MarkerDetector for detecting markers of type M |
| alvar::MarkerDetectorEC< M > | Version of MarkerDetector using external container |
| alvar::MarkerDetectorImpl | Templateless version of MarkerDetector. Please use MarkerDetector instead |
| alvar::MarkerIterator | Iterator type for traversing templated Marker vector without the template |
| alvar::MarkerIteratorImpl< T > | Iterator implementation for traversing templated Marker vector without the template |
| alvar::MultiMarkerInitializer::MarkerMeasurement | MarkerMeasurement that holds the maker id |
| ros::message_traits::MD5Sum< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_traits::MD5Sum< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| ar_track_alvar::MedianFilter | |
| alvar::MultiMarker | Base class for using MultiMarker |
| alvar::MultiMarkerBundle | Multi marker that uses bundle adjustment to refine the 3D positions of the markers (point cloud) |
| alvar::MultiMarkerEC | Version of MultiMarker using external container |
| alvar::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 |
| alvar::MultiMarkerInitializer | Initializes multi marker by estimating their relative positions from one or more images |
| alvar::Mutex | Mutex for synchronizing multiple threads |
| alvar::MutexPrivate | |
| alvar::MutexPrivateData | |
| alvar::Optimization | Non-linear optimization routines. There are three methods implemented that include Gauss-Newton, Levenberg-Marquardt and Tukey m-estimator |
| OwnDrawable | |
| ar_track_alvar::PlaneFitResult | |
| alvar::Plugin | Plugin for loading dynamic libraries |
| alvar::PluginPrivate | |
| alvar::PluginPrivateData | |
| alvar::Point< C, D > | Simple Point class meant to be inherited from OpenCV point-classes. For example: Point<CvPoint2D64f> p |
| alvar::Pose | Pose representation derived from the Rotation class |
| ros::message_operations::Printer< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::message_operations::Printer< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| alvar::ProjectParams | |
| alvar::ProjPoints | Simple structure for collecting 2D and 3D points e.g. for camera calibration |
| alvar::Ransac< MODEL, PARAMETER > | Implementation of a general RANdom SAmple Consensus algorithm |
| alvar::RansacImpl | Internal implementation of RANSAC. Please use Ransac or IndexRansac |
| alvar::Rotation | Rotation structure and transformations between different parameterizations |
| alvar::Serialization | Class for serializing class content to/from file or std::iostream |
| alvar::SerializationFormatterXml | |
| ros::serialization::Serializer< ::ar_track_alvar::AlvarMarker_< ContainerAllocator > > | |
| ros::serialization::Serializer< ::ar_track_alvar::AlvarMarkers_< ContainerAllocator > > | |
| alvar::SimpleSfM | Simple structure from motion implementation using CameraEC , MarkerDetectorEC and TrackerFeaturesEC |
| alvar::StartThreadParameters | |
| State | |
| alvar::Threads | Threads vector for handling multiple threads |
| alvar::ThreadsPrivate | |
| alvar::ThreadsPrivateData | |
| alvar::Timer | Timer for measuring execution time |
| alvar::TimerPrivate | |
| alvar::TimerPrivateData | |
| alvar::Tracker | Pure virtual base class for tracking optical flow |
| alvar::TrackerFeatures | TrackerFeatures tracks features using OpenCV's cvGoodFeaturesToTrack and cvCalcOpticalFlowPyrLK |
| alvar::TrackerFeaturesEC | Version of TrackerFeatures using external container |
| alvar::TrackerOrientation | Track orientation based only on features in the image plane |
| alvar::TrackerPsa | TrackerPsa implements a very simple PSA tracker |
| alvar::TrackerPsaRot | TrackerPsaRot implements a slightly extended version of a TrackerPsa which can also detect sideways rotation |
| alvar::TrackerStat | TrackerStat deduces the optical flow based on tracked features using Seppo Valli's statistical tracking |
| alvar::TrackerStatRot | TrackerStatRot implements a slightly extended version of TrackerStat which can also detect sideways rotation |
| alvar::TrifocalTensor | Trifocal tensor works for three images like a fundamental matrix works for two images |
| alvar::Uncopyable | Uncopyable for preventing object copies |
| alvar::UnscentedKalman | Implementation of unscented kalman filter (UKF) for filtering non-linear processes |
| alvar::UnscentedObservation | Observation model for an unscented kalman filter |
| alvar::UnscentedProcess | Process model for an unscented kalman filter |
| alvar::plugins::CaptureDSCapture::VideoSampler |