35 #include <pcl/point_types.h> 36 #include <Eigen/Geometry> 38 #include <boost/shared_ptr.hpp> 45 #include "wrappers/matrix/matrix_wrapper.h" 63 double& y,
double& z,
double& roll,
64 double& pitch,
double& yaw);
78 Eigen::Transform<double, 3, Eigen::Affine> &t);
95 std::vector<Feature::Id> vector_ids);
106 std::ostream&
operator <<(std::ostream& os, Eigen::Twistd twistd);
213 bool isFinite(
const Eigen::Matrix4d& transformation);
221 void ROSTwist2EigenTwist(
const geometry_msgs::Twist& ros_twist, Eigen::Twistd &eigen_twist);
223 Eigen::Twistd
unwrapTwist(Eigen::Twistd& current_twist, Eigen::Displacementd& current_displacement, Eigen::Twistd& previous_twist,
bool &changed);
225 Eigen::Twistd
invertTwist(Eigen::Twistd& current_twist, Eigen::Twistd& previous_twist,
bool& inverted);
227 void invert3x3Matrix(
const MatrixWrapper::Matrix& to_inv, MatrixWrapper::Matrix& inverse);
229 void invert3x3MatrixEigen(
const Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& to_inv,
230 Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& inverse);
boost::tuple< double, double, double > Location
Feature::Location operator-(const Feature::Location &location1, const Feature::Location &location2)
void EigenAffine2TranslationAndEulerAngles(const Eigen::Affine3d &t, double &x, double &y, double &z, double &roll, double &pitch, double &yaw)
double L2Distance(const Feature::Location &first, const Feature::Location &second)
void TransformMatrix2Twist(const Eigen::Matrix4d &transformation_matrix, Eigen::Twistd &twist)
bool isFinite(const Eigen::Matrix4d &transformation)
Feature::Location operator+(const Feature::Location &location1, const Feature::Location &location2)
void Twist2TransformMatrix(const Eigen::Twistd &transformation_twist, Eigen::Matrix4d &matrix)
void TranslationAndEulerAngles2EigenAffine(const double &x, const double &y, const double &z, const double &roll, const double &pitch, const double &yaw, Eigen::Transform< double, 3, Eigen::Affine > &t)
void ROSTwist2EigenTwist(const geometry_msgs::Twist &ros_twist, Eigen::Twistd &eigen_twist)
void LocationOfFeature2ColumnVectorHomogeneous(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec)
void invert3x3MatrixEigen2(const Eigen::Matrix3d &to_inv, Eigen::Matrix3d &inverse)
double sampleNormal(double mean, double std_dev)
Eigen::Twistd unwrapTwist(Eigen::Twistd ¤t_twist, Eigen::Displacementd ¤t_displacement, Eigen::Twistd &previous_twist, bool &changed)
void TransformMatrix2TwistUnwrapped(const Eigen::Matrix4d &transformation_matrix, Eigen::Twistd &twist, const Eigen::Twistd &twist_previous)
void invert3x3Matrix(const MatrixWrapper::Matrix &to_inv, MatrixWrapper::Matrix &inverse)
void LocationOfFeature2ColumnVector(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec)
void LocationOfFeature2EigenVectorHomogeneous(const Feature::Location &lof, Eigen::Vector4d &eig_vec)
void LocationAndId2FeaturePCL(const Feature::Location &feature_location, const Feature::Id &feature_id, pcl::PointXYZL &feature_pcl)
void GeometryMsgsTwist2EigenTwist(const geometry_msgs::Twist &gm_twist, Eigen::Twistd &eigen_twist)
void TransformLocation(const Feature::Location &origin, const Eigen::Matrix4d &transformation, Feature::Location &new_location)
void LocationAndId2FeaturePCLwc(const Feature::Location &feature_location, const Feature::Id &feature_id, omip::FeaturePCLwc &feature_pcl)
std::ostream & operator<<(std::ostream &os, std::vector< Feature::Id > vector_ids)
void invert3x3MatrixEigen(const Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > > &to_inv, Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > > &inverse)
void Location2PointPCL(const Feature::Location &point_location, pcl::PointXYZ &point_pcl)
Eigen::Twistd invertTwist(Eigen::Twistd ¤t_twist, Eigen::Twistd &previous_twist, bool &inverted)
void EigenTwist2GeometryMsgsTwist(Eigen::Twistd &eigen_twist, geometry_msgs::Twist &gm_twist)