Public Member Functions
alvar::CameraEC Class Reference

Version of Camera using external container. More...

#include <EC.h>

Inheritance diagram for alvar::CameraEC:
Inheritance graph
[legend]

List of all members.

Public Member Functions

template<typename T >
bool CalcExteriorOrientation (std::map< int, T > &container, Pose *pose, int type_id=-1)
 Calculate the pose using the items with matching type_id.
template<typename T , typename F >
bool CalcExteriorOrientation (std::map< int, T > &container, Pose *pose, F do_handle_test)
 Calculate the pose using the items matching the given functor.
template<typename T >
void Distort (std::map< int, T > &container, int type_id=-1)
 Distort the items with matching type_id.
template<typename T , typename F >
void Distort (std::map< int, T > &container, F &do_handle_test)
 Distort the items matching the given functor.
template<typename T >
int EraseUsingReprojectionError (std::map< int, T > &container, float reprojection_error_limit, int type_id=-1, Pose *pose=0)
 Erases the items matching with type_id having large reprojection error. If type_id == -1 doesn't test the type. If pose is given calls Reproject() internally -- otherwise assumes it has been called beforehands.
void Get3dOnDepth (const Pose *pose, CvPoint2D32f p2d, float depth, CvPoint3D32f &p3d)
 Get 3D-coordinate for 2D feature assuming certain depth.
void Get3dOnPlane (const Pose *pose, CvPoint2D32f p2d, CvPoint3D32f &p3d)
 Get 3D-coordinate for 2D feature on the plane defined by the pose (z == 0)
bool ReconstructFeature (const Pose *pose1, const Pose *pose2, const CvPoint2D32f *u1, const CvPoint2D32f *u2, CvPoint3D32f *p3d, double limit)
 Reconstruct 3D point using two camera poses and corresponding undistorted image feature positions.
template<typename T >
float Reproject (std::map< int, T > &container, Pose *pose, int type_id=-1, bool needs_has_p2d=false, bool needs_has_p3d=false, float average_outlier_limit=0.f)
 Projects p3d in the items matching with type_id into projected_p2d . If type_id == -1 doesn't test the type.
template<typename T , typename F >
float Reproject (std::map< int, T > &container, Pose *pose, F do_handle_test, float average_outlier_limit=0.f)
 Projects p3d in the items matching with the given functor.
template<typename T >
void Undistort (std::map< int, T > &container, int type_id=-1)
 Undistort the items with matching type_id.
template<typename T , typename F >
void Undistort (std::map< int, T > &container, F &do_handle_test)
 Undistort the items matching the given functor.
template<typename T >
bool UpdatePose (std::map< int, T > &container, Pose *pose, int type_id=-1, std::map< int, double > *weights=0)
 Update the pose using the items with matching type_id.
template<typename T , typename F >
bool UpdatePose (std::map< int, T > &container, Pose *pose, F do_handle_test, std::map< int, double > *weights=0)
 Update the pose using the items matching the given functor.
bool UpdatePose (const CvMat *object_points, CvMat *image_points, Pose *pose, CvMat *weights=0)
 Update existing pose based on new observations.
bool UpdatePose (const CvMat *object_points, CvMat *image_points, CvMat *rodriques, CvMat *tra, CvMat *weights=0)
 Update existing pose (in rodriques&tra) based on new observations.
template<typename T >
bool UpdateRotation (std::map< int, T > &container, Pose *pose, int type_id=-1)
 Update the rotation in pose using the items with matching type_id.
template<typename T , typename F >
bool UpdateRotation (std::map< int, T > &container, Pose *pose, F do_handle_test)
 Update the rotation in pose using the items matching the given functor.
bool UpdateRotation (const CvMat *object_points, CvMat *image_points, Pose *pose)
 Update pose rotations based on new observations.
bool UpdateRotation (const CvMat *object_points, CvMat *image_points, CvMat *rot, CvMat *tra)
 Update pose rotations (in rodriques&tra) based on new observations.

Detailed Description

Version of Camera using external container.

Definition at line 392 of file EC.h.


Member Function Documentation

template<typename T >
bool alvar::CameraEC::CalcExteriorOrientation ( std::map< int, T > &  container,
Pose pose,
int  type_id = -1 
) [inline]

Calculate the pose using the items with matching type_id.

Definition at line 430 of file EC.h.

template<typename T , typename F >
bool alvar::CameraEC::CalcExteriorOrientation ( std::map< int, T > &  container,
Pose pose,
do_handle_test 
) [inline]

Calculate the pose using the items matching the given functor.

Definition at line 436 of file EC.h.

template<typename T >
void alvar::CameraEC::Distort ( std::map< int, T > &  container,
int  type_id = -1 
) [inline]

Distort the items with matching type_id.

Definition at line 413 of file EC.h.

template<typename T , typename F >
void alvar::CameraEC::Distort ( std::map< int, T > &  container,
F &  do_handle_test 
) [inline]

Distort the items matching the given functor.

Definition at line 419 of file EC.h.

template<typename T >
int alvar::CameraEC::EraseUsingReprojectionError ( std::map< int, T > &  container,
float  reprojection_error_limit,
int  type_id = -1,
Pose pose = 0 
) [inline]

Erases the items matching with type_id having large reprojection error. If type_id == -1 doesn't test the type. If pose is given calls Reproject() internally -- otherwise assumes it has been called beforehands.

Definition at line 618 of file EC.h.

void alvar::CameraEC::Get3dOnDepth ( const Pose pose,
CvPoint2D32f  p2d,
float  depth,
CvPoint3D32f &  p3d 
)

Get 3D-coordinate for 2D feature assuming certain depth.

Definition at line 252 of file EC.cpp.

void alvar::CameraEC::Get3dOnPlane ( const Pose pose,
CvPoint2D32f  p2d,
CvPoint3D32f &  p3d 
)

Get 3D-coordinate for 2D feature on the plane defined by the pose (z == 0)

Definition at line 215 of file EC.cpp.

bool alvar::CameraEC::ReconstructFeature ( const Pose pose1,
const Pose pose2,
const CvPoint2D32f *  u1,
const CvPoint2D32f *  u2,
CvPoint3D32f *  p3d,
double  limit 
)

Reconstruct 3D point using two camera poses and corresponding undistorted image feature positions.

Definition at line 196 of file EC.cpp.

template<typename T >
float alvar::CameraEC::Reproject ( std::map< int, T > &  container,
Pose pose,
int  type_id = -1,
bool  needs_has_p2d = false,
bool  needs_has_p3d = false,
float  average_outlier_limit = 0.f 
) [inline]

Projects p3d in the items matching with type_id into projected_p2d . If type_id == -1 doesn't test the type.

Definition at line 581 of file EC.h.

template<typename T , typename F >
float alvar::CameraEC::Reproject ( std::map< int, T > &  container,
Pose pose,
do_handle_test,
float  average_outlier_limit = 0.f 
) [inline]

Projects p3d in the items matching with the given functor.

Definition at line 588 of file EC.h.

template<typename T >
void alvar::CameraEC::Undistort ( std::map< int, T > &  container,
int  type_id = -1 
) [inline]

Undistort the items with matching type_id.

Definition at line 396 of file EC.h.

template<typename T , typename F >
void alvar::CameraEC::Undistort ( std::map< int, T > &  container,
F &  do_handle_test 
) [inline]

Undistort the items matching the given functor.

Definition at line 402 of file EC.h.

template<typename T >
bool alvar::CameraEC::UpdatePose ( std::map< int, T > &  container,
Pose pose,
int  type_id = -1,
std::map< int, double > *  weights = 0 
) [inline]

Update the pose using the items with matching type_id.

Definition at line 473 of file EC.h.

template<typename T , typename F >
bool alvar::CameraEC::UpdatePose ( std::map< int, T > &  container,
Pose pose,
do_handle_test,
std::map< int, double > *  weights = 0 
) [inline]

Update the pose using the items matching the given functor.

Definition at line 526 of file EC.h.

bool alvar::CameraEC::UpdatePose ( const CvMat *  object_points,
CvMat *  image_points,
Pose pose,
CvMat *  weights = 0 
)

Update existing pose based on new observations.

Definition at line 63 of file EC.cpp.

bool alvar::CameraEC::UpdatePose ( const CvMat *  object_points,
CvMat *  image_points,
CvMat *  rodriques,
CvMat *  tra,
CvMat *  weights = 0 
)

Update existing pose (in rodriques&tra) based on new observations.

Definition at line 74 of file EC.cpp.

template<typename T >
bool alvar::CameraEC::UpdateRotation ( std::map< int, T > &  container,
Pose pose,
int  type_id = -1 
) [inline]

Update the rotation in pose using the items with matching type_id.

Definition at line 479 of file EC.h.

template<typename T , typename F >
bool alvar::CameraEC::UpdateRotation ( std::map< int, T > &  container,
Pose pose,
do_handle_test 
) [inline]

Update the rotation in pose using the items matching the given functor.

Definition at line 485 of file EC.h.

bool alvar::CameraEC::UpdateRotation ( const CvMat *  object_points,
CvMat *  image_points,
Pose pose 
)

Update pose rotations based on new observations.

Definition at line 101 of file EC.cpp.

bool alvar::CameraEC::UpdateRotation ( const CvMat *  object_points,
CvMat *  image_points,
CvMat *  rot,
CvMat *  tra 
)

Update pose rotations (in rodriques&tra) based on new observations.

Definition at line 113 of file EC.cpp.


The documentation for this class was generated from the following files:


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 21:12:55