ethzasl-msf - Modular Sensor Fusion
Time delay compensated single and multi sensor fusion framework based on an EKF
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Classes | Namespaces | Typedefs | Enumerations | Functions
similaritytransform.h File Reference
#include <vector>
#include <utility>
#include <geometry_msgs/PoseWithCovariance.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <limits>
#include <msf_core/msf_types.hpp>
#include <msf_core/eigen_utils.h>

Go to the source code of this file.

Classes

class  msf_core::similarity_transform::From6DoF
 Computes the average similarity transform (rotation, position, scale) between two sets of 6 DoF poses. More...

Namespaces

namespace  geometry_msgs
 Defines the start row and col for the covariance entries in.
namespace  geometry_msgs::cov
namespace  msf_core
namespace  msf_core::similarity_transform

Typedefs

typedef
geometry_msgs::PoseWithCovariance 
msf_core::similarity_transform::Pose
typedef std::pair< Pose, Pose > msf_core::similarity_transform::PosePair
typedef std::vector< PosePair > msf_core::similarity_transform::PosePairVector

Enumerations

enum  { geometry_msgs::cov::p = 0, geometry_msgs::cov::q = 3 }

Functions

Vector3 msf_core::geometry_msgsToEigen (const geometry_msgs::Point &p)
 Converts a geometry_msgs::Point to an Eigen Vector3d.
Eigen::Quaterniond msf_core::geometry_msgsToEigen (const geometry_msgs::Quaternion &q)
 Converts a geometry_msgs::Quaternion to an Eigen::Quaterniond.
Matrix3 msf_core::geometry_msgsCovBlockToEigen (const geometry_msgs::PoseWithCovariance::_covariance_type &gcov, int start_row, int start_col)
 Returns a 3x3 covariance block entry from a geometry_msgs::PoseWithCovariance::covariance array.
template<class Derived >
void msf_core::eigenCovBlockToGeometry_msgs (geometry_msgs::PoseWithCovariance::_covariance_type &gcov, const Eigen::MatrixBase< Derived > &ecov, int start_row, int start_col)
 Fills a 3x3 covariance block entry of a geometry_msgs::PoseWithCovariance::covariance array from an Eigen 3x3 matrix.
template<class Derived >
geometry_msgs::Point msf_core::eigenToGeometry_msgs (const Eigen::MatrixBase< Derived > &p)
 Converts any eigen vector with 3 elements to a geometry_msgs::Point.
geometry_msgs::Quaternion msf_core::eigenToGeometry_msgs (const Eigen::Quaterniond &q)
 Converts an Eigen::Quaterniond to a geometry_msgs::Quaternion.