Namespaces | |
namespace | msg |
Classes | |
struct | CameraNode_ |
class | Con2dP2 |
class | ConP2 |
class | ConP3P |
class | ConScale |
class | CSparse |
class | CSparse2d |
struct | Frame_ |
class | JacobProds |
class | Node |
NODE holds graph nodes corresponding to frames, for use in sparse bundle adjustment. Each node has a 6DOF pose, encoded as a translation vector and rotation unit quaternion (Eigen classes). These represent the pose of the node in the world frame. More... | |
class | Node2d |
class | Proj |
Proj holds a projection measurement of a point onto a frame. They are a repository for the link between the frame and the point, with auxillary info such as Jacobians. More... | |
struct | Projection_ |
class | SysSBA |
SysSBA holds a set of nodes and points for sparse bundle adjustment. More... | |
class | SysSPA |
SysSPA holds a set of nodes and constraints for sparse pose adjustment. More... | |
class | SysSPA2d |
SysSPA2d holds a set of nodes and constraints for sparse pose adjustment. More... | |
class | Track |
struct | WorldPoint_ |
Typedefs | |
typedef ::sba::CameraNode_ < std::allocator< void > > | CameraNode |
typedef boost::shared_ptr < ::sba::CameraNode const > | CameraNodeConstPtr |
typedef boost::shared_ptr < ::sba::CameraNode > | CameraNodePtr |
typedef ::sba::Frame_ < std::allocator< void > > | Frame |
typedef boost::shared_ptr < ::sba::Frame const > | FrameConstPtr |
typedef boost::shared_ptr < ::sba::Frame > | FramePtr |
typedef Eigen::Vector3d | Keypoint |
Keypoints - subpixel using floats. u,v are pixel coordinates, d is disparity (if stereo). | |
typedef Eigen::Vector4d | Point |
Point holds 3D points using in world coordinates. Currently we just represent these as 4-vectors, with a final "1.0". | |
typedef ::sba::Projection_ < std::allocator< void > > | Projection |
typedef boost::shared_ptr < ::sba::Projection const > | ProjectionConstPtr |
typedef boost::shared_ptr < ::sba::Projection > | ProjectionPtr |
typedef std::map< const int, Proj, std::less< int > , Eigen::aligned_allocator < Proj > > | ProjMap |
typedef ::sba::WorldPoint_ < std::allocator< void > > | WorldPoint |
typedef boost::shared_ptr < ::sba::WorldPoint const > | WorldPointConstPtr |
typedef boost::shared_ptr < ::sba::WorldPoint > | WorldPointPtr |
Functions | |
void | drawGraph (const SysSBA &sba, const ros::Publisher &camera_pub, const ros::Publisher &point_pub, int decimation=1, int bicolor=0) |
static int | getind (std::map< int, int > &m, int ind) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sba::WorldPoint_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sba::Projection_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sba::Frame_< ContainerAllocator > &v) |
template<typename ContainerAllocator > | |
std::ostream & | operator<< (std::ostream &s, const ::sba::CameraNode_< ContainerAllocator > &v) |
int | ParseBundlerFile (const char *fin, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camp, std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > &camR, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camt, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ptp, std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > &ptc, std::vector< std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > > &ptt) |
A low-level parser for bundler files. | |
int | ParseGraphFile (const char *fin, std::vector< Eigen::Vector5d, Eigen::aligned_allocator< Eigen::Vector5d > > &camps, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &camqs, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camts, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ptps, std::vector< std::vector< Eigen::Vector11d, Eigen::aligned_allocator< Eigen::Vector11d > > > &ptts) |
A low-level parser for graph files. | |
int | ParseSPAGraphFile (const char *fin, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ntrans, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &nqrot, std::vector< Eigen::Vector2i, Eigen::aligned_allocator< Eigen::Vector2i > > &cind, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ctrans, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &cqrot, std::vector< Eigen::Matrix< double, 6, 6 >, Eigen::aligned_allocator< Eigen::Matrix< double, 6, 6 > > > &cvar) |
A low-level parser for graph files. | |
bool | read2dP2File (char *fname, SysSPA2d spa) |
constraint files | |
int | readBundlerFile (const char *filename, sba::SysSBA &sbaout) |
Reads bundle adjustment data from a Bundler file to an instance of SysSBA. | |
int | readGraphFile (const char *filename, sba::SysSBA &sbaout) |
Reads bundle adjustment data from a graph-type file to an instance of SysSBA. | |
bool | readP2File (char *fname, SysSPA spa) |
constraint files | |
int | readSPAGraphFile (const char *filename, SysSPA &spaout) |
Reads 3D pose graph data from a graph-type file to an instance of SysSPA. | |
void | transformF2W (Eigen::Matrix< double, 3, 4 > &m, const Eigen::Matrix< double, 4, 1 > &trans, const Eigen::Quaternion< double > &qrot) |
void | transformN2N (Eigen::Matrix< double, 4, 1 > &trans, Eigen::Quaternion< double > &qrot, Node &nd0, Node &nd1) |
void | transformW2F (Eigen::Matrix< double, 3, 4 > &m, const Eigen::Matrix< double, 4, 1 > &trans, const Eigen::Quaternion< double > &qrot) |
void | writeA (const char *fname, SysSBA &sba) |
int | writeBundlerFile (const char *filename, sba::SysSBA &sbain) |
Writes bundle adjustment data from an instance of SysSBA to a Bundler file. | |
int | writeGraphFile (const char *filename, SysSBA &sba, bool mono=false) |
Writes out the current SBA system as an ascii graph file suitable to be read in by the Freiburg HChol system. <mono> is true if only monocular projections are desired. | |
void | writeLourakisFile (const char *fname, SysSBA &sba) |
write out system in SBA form | |
void | writeSparseA (const char *fname, SysSBA &sba) |
typedef ::sba::CameraNode_<std::allocator<void> > sba::CameraNode |
Definition at line 176 of file CameraNode.h.
typedef boost::shared_ptr< ::sba::CameraNode const> sba::CameraNodeConstPtr |
Definition at line 179 of file CameraNode.h.
typedef boost::shared_ptr< ::sba::CameraNode> sba::CameraNodePtr |
Definition at line 178 of file CameraNode.h.
typedef ::sba::Frame_<std::allocator<void> > sba::Frame |
typedef boost::shared_ptr< ::sba::Frame const> sba::FrameConstPtr |
typedef boost::shared_ptr< ::sba::Frame> sba::FramePtr |
typedef Eigen::Vector3d sba::Keypoint |
typedef Eigen::Vector4d sba::Point |
typedef ::sba::Projection_<std::allocator<void> > sba::Projection |
Definition at line 162 of file Projection.h.
typedef boost::shared_ptr< ::sba::Projection const> sba::ProjectionConstPtr |
Definition at line 165 of file Projection.h.
typedef boost::shared_ptr< ::sba::Projection> sba::ProjectionPtr |
Definition at line 164 of file Projection.h.
typedef std::map<const int, Proj, std::less<int>, Eigen::aligned_allocator<Proj> > sba::ProjMap |
typedef ::sba::WorldPoint_<std::allocator<void> > sba::WorldPoint |
Definition at line 123 of file WorldPoint.h.
typedef boost::shared_ptr< ::sba::WorldPoint const> sba::WorldPointConstPtr |
Definition at line 126 of file WorldPoint.h.
typedef boost::shared_ptr< ::sba::WorldPoint> sba::WorldPointPtr |
Definition at line 125 of file WorldPoint.h.
void sba::drawGraph | ( | const SysSBA & | sba, | |
const ros::Publisher & | camera_pub, | |||
const ros::Publisher & | point_pub, | |||
int | decimation = 1 , |
|||
int | bicolor = 0 | |||
) |
Definition at line 5 of file visualization.cpp.
static int sba::getind | ( | std::map< int, int > & | m, | |
int | ind | |||
) | [inline, static] |
Run the LM algorithm that computes a nonlinear SPA estimate. <window> is the number of nodes in the window, the last nodes added <niter> is the max number of iterations to perform; returns the number actually performed. <lambda> is the diagonal augmentation for LM. <useCSParse> = 0 for dense Cholesky, 1 for sparse Cholesky, 2 for sparse PCG
std::ostream& sba::operator<< | ( | std::ostream & | s, | |
const ::sba::WorldPoint_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 130 of file WorldPoint.h.
std::ostream& sba::operator<< | ( | std::ostream & | s, | |
const ::sba::Projection_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 169 of file Projection.h.
std::ostream& sba::operator<< | ( | std::ostream & | s, | |
const ::sba::Frame_< ContainerAllocator > & | v | |||
) | [inline] |
std::ostream& sba::operator<< | ( | std::ostream & | s, | |
const ::sba::CameraNode_< ContainerAllocator > & | v | |||
) | [inline] |
Definition at line 183 of file CameraNode.h.
int sba::ParseBundlerFile | ( | const char * | fin, | |
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | camp, | |||
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > & | camR, | |||
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | camt, | |||
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | ptp, | |||
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > & | ptc, | |||
std::vector< std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > > & | ptt | |||
) |
A low-level parser for bundler files.
int sba::ParseGraphFile | ( | const char * | fin, | |
std::vector< Eigen::Vector5d, Eigen::aligned_allocator< Eigen::Vector5d > > & | camps, | |||
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > & | camqs, | |||
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | camts, | |||
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | ptps, | |||
std::vector< std::vector< Eigen::Vector11d, Eigen::aligned_allocator< Eigen::Vector11d > > > & | ptts | |||
) |
A low-level parser for graph files.
int sba::ParseSPAGraphFile | ( | const char * | fin, | |
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | ntrans, | |||
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > & | nqrot, | |||
std::vector< Eigen::Vector2i, Eigen::aligned_allocator< Eigen::Vector2i > > & | cind, | |||
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > & | ctrans, | |||
std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > & | cqrot, | |||
std::vector< Eigen::Matrix< double, 6, 6 >, Eigen::aligned_allocator< Eigen::Matrix< double, 6, 6 > > > & | cvar | |||
) |
A low-level parser for graph files.
Definition at line 996 of file sba_file_io.cpp.
bool sba::read2dP2File | ( | char * | fname, | |
SysSPA2d | spa | |||
) |
constraint files
reads in a file of pose constraints
int sba::readBundlerFile | ( | const char * | filename, | |
sba::SysSBA & | sbaout | |||
) |
Reads bundle adjustment data from a Bundler file to an instance of SysSBA.
filename | The name of the bundler-formatted file to read from. | |
sbaout | An instance of SBA that the file will be written to. It should be noted that the bundler format does not support stereo points; all points read in will be monocular. Note: documentation of the Bundler format can be found at http://phototour.cs.washington.edu/bundler/bundler-v0.3-manual.html . |
Definition at line 9 of file sba_file_io.cpp.
int sba::readGraphFile | ( | const char * | filename, | |
sba::SysSBA & | sbaout | |||
) |
Reads bundle adjustment data from a graph-type file to an instance of SysSBA.
filename | The name of the bundler-formatted file to read from. | |
sbaout | An instance of SBA that the file will be written to. Note: where is the documentation for this format? |
Definition at line 488 of file sba_file_io.cpp.
bool sba::readP2File | ( | char * | fname, | |
SysSPA | spa | |||
) |
int sba::readSPAGraphFile | ( | const char * | filename, | |
SysSPA & | spaout | |||
) |
Reads 3D pose graph data from a graph-type file to an instance of SysSPA.
filename | The name of the bundler-formatted file to read from. | |
spaout | An instance of SPA that the file will be written to. Note: where is the documentation for this format? |
Definition at line 929 of file sba_file_io.cpp.
void sba::transformF2W | ( | Eigen::Matrix< double, 3, 4 > & | m, | |
const Eigen::Matrix< double, 4, 1 > & | trans, | |||
const Eigen::Quaternion< double > & | qrot | |||
) |
void sba::transformN2N | ( | Eigen::Matrix< double, 4, 1 > & | trans, | |
Eigen::Quaternion< double > & | qrot, | |||
Node & | nd0, | |||
Node & | nd1 | |||
) |
void sba::transformW2F | ( | Eigen::Matrix< double, 3, 4 > & | m, | |
const Eigen::Matrix< double, 4, 1 > & | trans, | |||
const Eigen::Quaternion< double > & | qrot | |||
) |
void sba::writeA | ( | const char * | fname, | |
SysSBA & | sba | |||
) |
Definition at line 401 of file sba_file_io.cpp.
int sba::writeBundlerFile | ( | const char * | filename, | |
sba::SysSBA & | sbain | |||
) |
Writes bundle adjustment data from an instance of SysSBA to a Bundler file.
filename | The name of the bundler-formatted file to write to. The file is created, or if it already exists, truncated. | |
sbain | An instance of SBA that the file will be written from. It should be noted that the bundler format does not support stereo points; all points written will be monocular. Also, since SBA does not store point color information, all points will be colored white. Note: documentation of the Bundler format can be found at http://phototour.cs.washington.edu/bundler/bundler-v0.3-manual.html . |
Definition at line 114 of file sba_file_io.cpp.
int sba::writeGraphFile | ( | const char * | filename, | |
SysSBA & | sba, | |||
bool | mono = false | |||
) |
Writes out the current SBA system as an ascii graph file suitable to be read in by the Freiburg HChol system. <mono> is true if only monocular projections are desired.
Definition at line 783 of file sba_file_io.cpp.
void sba::writeLourakisFile | ( | const char * | fname, | |
SysSBA & | sba | |||
) |
write out system in SBA form
Definition at line 322 of file sba_file_io.cpp.
void sba::writeSparseA | ( | const char * | fname, | |
SysSBA & | sba | |||
) |
Definition at line 418 of file sba_file_io.cpp.