$search
Classes | |
struct | ActivePathUniformCostFunction |
struct | CholOptimizer |
struct | CovariancePropagator |
struct | Dijkstra |
struct | Gradient |
struct | Gradient< PoseGraph2D > |
struct | Gradient< PoseGraph3D > |
struct | Graph |
class | GraphOptimizer |
base for all optimizers More... | |
struct | HCholOptimizer |
struct | LoadedEdge |
struct | LoadedEdge3D |
struct | LoadedEdgeComparator |
struct | LoadedEdgeComparator3D |
struct | LocalGradient |
struct | LocalGradient< PoseGraph2D > |
struct | LocalGradient< PoseGraph3D > |
struct | ManifoldGradient |
struct | ManifoldGradient< PoseGraph2D > |
struct | ManifoldGradient< PoseGraph3D > |
struct | MotionJacobian |
struct | MotionJacobian< PoseGraph< Transformation2, Matrix3 > > |
struct | MotionJacobian< PoseGraph< Transformation3, Matrix6 > > |
struct | PoseGraph |
struct | PoseGraph2D |
struct | PoseGraph3D |
class | PoseGraph3DVis |
visualization of a pose graph (using a pointer to the graph) More... | |
struct | PosePropagator |
struct | PoseUpdate |
struct | PoseUpdate< PoseGraph2D > |
struct | PoseUpdate< PoseGraph3D > |
class | QGLGraphViewer |
struct | SparseMatrixEntry |
struct | SparseMatrixEntryPtrCmp |
class | StandardCamera |
struct | TaylorTerms |
struct | TaylorTerms< PoseGraph2D > |
struct | TaylorTerms< PoseGraph3D > |
struct | TransformCovariance |
struct | TransformCovariance< PoseGraph2D > |
struct | TransformCovariance< PoseGraph3D > |
struct | UniformCostFunction |
Typedefs | |
typedef CholOptimizer < PoseGraph2D > | CholOptimizer2D |
the 2D cholesky optimizer | |
typedef CholOptimizer < PoseGraph3D > | CholOptimizer3D |
the 2D cholesky optimizer | |
typedef GraphOptimizer < PoseGraph3D > | GraphOptimizer3D |
typedef HCholOptimizer < PoseGraph2D > | HCholOptimizer2D |
2D hirachical cholesky optimizer | |
typedef HCholOptimizer < PoseGraph3D > | HCholOptimizer3D |
3D hirachical cholesky optimizer | |
typedef std::set< LoadedEdge, LoadedEdgeComparator > | LoadedEdgeSet |
typedef std::set< LoadedEdge3D, LoadedEdgeComparator3D > | LoadedEdgeSet3D |
typedef GraphOptimizer < PoseGraph2D > | Optimizer2D |
Functions | |
std::string | changeFileExtension (const std::string &filename, const std::string &newExt, bool stripDot=false) |
void | connectedSubset (Graph::VertexSet &connected, Graph::VertexSet &visited, Graph::VertexSet &startingSet, Graph *g, Graph::Vertex *v, Dijkstra::CostFunction *cost, double distance, double comparisonConditioner) |
bool | createDirectory (const char *dirName, bool pub=false) |
csn * | cs_chol_workspace (const cs *A, const css *S, int *cin, double *xin) |
int | cs_cholsolinvblocksymb (const cs *A, double **block, int r1, int c1, int r2, int c2, double *y, const css *S, double *x, double *b, double *temp, int *work) |
int | cs_cholsolsymb (const cs *A, double *b, const css *S, double *workspace, int *work) |
void | eulerGradientXi (Matrix6 &mat, const Vector6 &e, const Vector6 &xi, const Vector6 &xj) |
void | eulerGradientXj (Matrix6 &mat, const Vector6 &e, const Vector6 &xi, const Vector6 &xj) |
bool | fileExists (const char *filename) |
std::string | getBasename (const std::string &filename) |
std::string | getCurrentDateAsFilename () |
std::vector< std::string > | getDirectoryElements (const char *dir, bool onlyFiles=false) |
std::string | getDirname (const std::string &filename) |
std::string | getFileExtension (const std::string &filename) |
std::vector< std::string > | getFilesByPattern (const char *pattern) |
off_t | getFileSize (const char *filename) |
time_t | getLastAccessDate (const char *filename) |
time_t | getLastModificationDate (const char *filename) |
time_t | getLastStatusChangeDate (const char *filename) |
std::string | getPureFilename (const std::string &filename) |
bool | isDirectory (const char *filename) |
bool | isRegularFile (const char *filename) |
bool | isSymbolicLink (const char *filename) |
void | loadEdges (LoadedEdgeSet &edges, istream &is, bool overrideCovariances) |
void | loadEdges (LoadedEdgeSet &edges, std::istream &is, bool overrideCovariances=false) |
void | loadEdges3D (LoadedEdgeSet3D &edges, std::istream &is, bool overrideCovariances=false) |
void | manifold2euler (Matrix6 &mat, double manifold[6]) |
void | manifoldGradientXi (Matrix6 &mat, const Vector6 &e, const Vector6 &xi, const Vector6 &xj) |
void | manifoldGradientXj (Matrix6 &mat, const Vector6 &e, const Vector6 &xi, const Vector6 &xj) |
void | manifoldZero2euler (Matrix6 &mat, double manifold[6]) |
void | motionJacobianMeasurement (Matrix6 &mat, const Vector6 &xi, const Vector6 &e) |
void | motionJacobianState (Matrix6 &mat, const Vector6 &xi, const Vector6 &e) |
bool | operator< (const Dijkstra::AdjacencyMapEntry &a, const Dijkstra::AdjacencyMapEntry &b) |
void | propagateJacobianManifold (Matrix6 &mat, const Vector6 &xi, const Vector6 &xj) |
cs_sparse * | SparseMatrixEntryPtrVector2CSparse (SparseMatrixEntry **entries, int r, int c, int nz) |
cs_sparse * | SparseMatrixEntryVector2CSparse (SparseMatrixEntry *entries, int r, int c, int nz) |
the 2D cholesky optimizer
Definition at line 28 of file include/hogman_minimal/graph_optimizer_hogman/graph_optimizer2d_chol.h.
the 2D cholesky optimizer
Definition at line 28 of file include/hogman_minimal/graph_optimizer_hogman/graph_optimizer3d_chol.h.
Definition at line 24 of file include/hogman_minimal/graph_optimizer/graph_optimizer3d.h.
2D hirachical cholesky optimizer
Definition at line 26 of file include/hogman_minimal/graph_optimizer_hogman/graph_optimizer2d_hchol.h.
3D hirachical cholesky optimizer
Definition at line 29 of file include/hogman_minimal/graph_optimizer_hogman/graph_optimizer3d_hchol.h.
typedef std::set< LoadedEdge, LoadedEdgeComparator > AISNavigation::LoadedEdgeSet |
Definition at line 51 of file include/hogman_minimal/graph_optimizer/graph_optimizer2d_aux.h.
typedef std::set< LoadedEdge3D, LoadedEdgeComparator3D > AISNavigation::LoadedEdgeSet3D |
Definition at line 55 of file include/hogman_minimal/graph/loadEdges3d.h.
typedef GraphOptimizer< PoseGraph2D > AISNavigation::Optimizer2D |
Definition at line 23 of file include/hogman_minimal/graph_optimizer/graph_optimizer2d.h.
std::string AISNavigation::changeFileExtension | ( | const std::string & | filename, | |
const std::string & | newExt, | |||
bool | stripDot = false | |||
) |
change the fileextension of a given filename. Only if filename contains an extension, otherwise filename is returned.
Definition at line 63 of file filesys_tools.cpp.
void AISNavigation::connectedSubset | ( | Graph::VertexSet & | connected, | |
Graph::VertexSet & | visited, | |||
Graph::VertexSet & | startingSet, | |||
Graph * | g, | |||
Graph::Vertex * | v, | |||
Dijkstra::CostFunction * | cost, | |||
double | distance, | |||
double | comparisonConditioner | |||
) |
Definition at line 162 of file dijkstra.cpp.
bool AISNavigation::createDirectory | ( | const char * | dirName, | |
bool | pub = false | |||
) |
create a directory. if pub is true, then the rights of the dir will be rwxrwxrwx (readable and writable for everyone)
Definition at line 91 of file csparse_helper.cpp.
int AISNavigation::cs_cholsolinvblocksymb | ( | const cs * | A, | |
double ** | block, | |||
int | r1, | |||
int | c1, | |||
int | r2, | |||
int | c2, | |||
double * | y, | |||
const css * | S, | |||
double * | x, | |||
double * | b, | |||
double * | temp, | |||
int * | work | |||
) |
Definition at line 47 of file csparse_helper.cpp.
int AISNavigation::cs_cholsolsymb | ( | const cs * | A, | |
double * | b, | |||
const css * | S, | |||
double * | workspace, | |||
int * | work | |||
) |
Definition at line 20 of file csparse_helper.cpp.
void AISNavigation::eulerGradientXi | ( | Matrix6 & | mat, | |
const Vector6 & | e, | |||
const Vector6 & | xi, | |||
const Vector6 & | xj | |||
) | [inline] |
Definition at line 446 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::eulerGradientXj | ( | Matrix6 & | mat, | |
const Vector6 & | e, | |||
const Vector6 & | xi, | |||
const Vector6 & | xj | |||
) | [inline] |
Definition at line 584 of file src/graph/posegraph3d_gradient.h.
bool AISNavigation::fileExists | ( | const char * | filename | ) |
check if file exists (note a directory is also a file)
Definition at line 75 of file filesys_tools.cpp.
std::string AISNavigation::getBasename | ( | const std::string & | filename | ) |
return the basename of the given filename /etc/fstab -> fstab
Definition at line 45 of file filesys_tools.cpp.
std::string AISNavigation::getCurrentDateAsFilename | ( | ) |
return the current date as a filename of the form YYYYMMDD_hhmmss
Definition at line 103 of file filesys_tools.cpp.
std::vector< std::string > AISNavigation::getDirectoryElements | ( | const char * | dir, | |
bool | onlyFiles = false | |||
) |
return all filenames in the given directory, may also be a sub directory if, onlyFiles is true, only files are returned
Definition at line 181 of file filesys_tools.cpp.
std::string AISNavigation::getDirname | ( | const std::string & | filename | ) |
return the directory of a given filename /etc/fstab -> /etc
Definition at line 54 of file filesys_tools.cpp.
std::string AISNavigation::getFileExtension | ( | const std::string & | filename | ) |
get filename extension (the part after the last .), e.g. the extension of file.txt is txt
Definition at line 27 of file filesys_tools.cpp.
std::vector< std::string > AISNavigation::getFilesByPattern | ( | const char * | pattern | ) |
return all files that match a given pattern, e.g., ~/blaa*.txt, /tmp/a*
Definition at line 207 of file filesys_tools.cpp.
off_t AISNavigation::getFileSize | ( | const char * | filename | ) |
return the size of the file in bytes.
Definition at line 171 of file filesys_tools.cpp.
time_t AISNavigation::getLastAccessDate | ( | const char * | filename | ) |
return date of last access to a file
Definition at line 123 of file filesys_tools.cpp.
time_t AISNavigation::getLastModificationDate | ( | const char * | filename | ) |
return the modification date of a file
Definition at line 113 of file filesys_tools.cpp.
time_t AISNavigation::getLastStatusChangeDate | ( | const char * | filename | ) |
return date of last status change of a file
Definition at line 133 of file filesys_tools.cpp.
std::string AISNavigation::getPureFilename | ( | const std::string & | filename | ) |
get the filename without the extension. file.txt -> file
Definition at line 36 of file filesys_tools.cpp.
bool AISNavigation::isDirectory | ( | const char * | filename | ) |
is the given filename a valid direcory, e.g. exists
Definition at line 87 of file filesys_tools.cpp.
bool AISNavigation::isRegularFile | ( | const char * | filename | ) |
checks if file exists and is a file
Definition at line 81 of file filesys_tools.cpp.
bool AISNavigation::isSymbolicLink | ( | const char * | filename | ) |
is the given file a symbolic link
Definition at line 93 of file filesys_tools.cpp.
void AISNavigation::loadEdges | ( | LoadedEdgeSet & | edges, | |
istream & | is, | |||
bool | overrideCovariances | |||
) |
Definition at line 25 of file graph_optimizer2d_aux.cpp.
void AISNavigation::loadEdges | ( | LoadedEdgeSet & | edges, | |
std::istream & | is, | |||
bool | overrideCovariances = false | |||
) |
void AISNavigation::loadEdges3D | ( | LoadedEdgeSet3D & | edges, | |
std::istream & | is, | |||
bool | overrideCovariances = false | |||
) |
Definition at line 25 of file loadEdges3d.cpp.
void AISNavigation::manifold2euler | ( | Matrix6 & | mat, | |
double | manifold[6] | |||
) | [inline] |
Definition at line 278 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::manifoldGradientXi | ( | Matrix6 & | mat, | |
const Vector6 & | e, | |||
const Vector6 & | xi, | |||
const Vector6 & | xj | |||
) | [inline] |
Definition at line 25 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::manifoldGradientXj | ( | Matrix6 & | mat, | |
const Vector6 & | e, | |||
const Vector6 & | xi, | |||
const Vector6 & | xj | |||
) | [inline] |
Definition at line 158 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::manifoldZero2euler | ( | Matrix6 & | mat, | |
double | manifold[6] | |||
) | [inline] |
Definition at line 385 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::motionJacobianMeasurement | ( | Matrix6 & | mat, | |
const Vector6 & | xi, | |||
const Vector6 & | e | |||
) | [inline] |
Definition at line 876 of file src/graph/posegraph3d_gradient.h.
void AISNavigation::motionJacobianState | ( | Matrix6 & | mat, | |
const Vector6 & | xi, | |||
const Vector6 & | e | |||
) | [inline] |
Definition at line 791 of file src/graph/posegraph3d_gradient.h.
bool AISNavigation::operator< | ( | const Dijkstra::AdjacencyMapEntry & | a, | |
const Dijkstra::AdjacencyMapEntry & | b | |||
) |
Definition at line 53 of file dijkstra.cpp.
void AISNavigation::propagateJacobianManifold | ( | Matrix6 & | mat, | |
const Vector6 & | xi, | |||
const Vector6 & | xj | |||
) | [inline] |
Definition at line 703 of file src/graph/posegraph3d_gradient.h.
cs_sparse * AISNavigation::SparseMatrixEntryPtrVector2CSparse | ( | SparseMatrixEntry ** | entries, | |
int | r, | |||
int | c, | |||
int | nz | |||
) | [inline] |
convert to csparse matrix, hoewever, we assume that the pointer are already sorted using the SparseMatrixEntryPtrCmp defined above
Definition at line 85 of file src/graph_optimizer_hogman/csparse_helper.h.
cs_sparse * AISNavigation::SparseMatrixEntryVector2CSparse | ( | SparseMatrixEntry * | entries, | |
int | r, | |||
int | c, | |||
int | nz | |||
) | [inline] |
Definition at line 54 of file src/graph_optimizer_hogman/csparse_helper.h.