Functions | |
| Eigen::Affine3d | direct_exponential_map (const Eigen::VectorXd &v, double delta_t) |
| double | f_mcosc (double cosx, double x) |
| double | f_msinc (double sinx, double x) |
| double | f_sinc (double sinx, double x) |
| bool | getTransform (const tf::TransformListener &listener, const std::string &target, const std::string source, Eigen::Affine3d &tMs, const ros::Time ×tamp=ros::Time::now(), const ros::Duration &timeout=ros::Duration(5.0)) |
| void | pseudoinverse (const Eigen::MatrixXd &M, Eigen::MatrixXd &Minv, double tolerance=1.e-06) |
| Eigen::MatrixXd | pseudoinverse (const Eigen::MatrixXd &M, double tolerance=1.e-06) |
| void | transformToPoseVector (const Eigen::Affine3d &M, Eigen::VectorXd &pose) |
| Eigen::VectorXd | transformToPoseVector (const Eigen::Affine3d &M) |
| Eigen::Affine3d | UThetaToAffine3d (const Eigen::Vector3d &u) |
Variables | |
| static const double | ang_min_mc = 2.5e-4 |
| static const double | ang_min_sinc = 1.0e-8 |
| Eigen::Affine3d eigen_utils::direct_exponential_map | ( | const Eigen::VectorXd & | v, |
| double | delta_t | ||
| ) |
Computes the direct exponential map for a twist acting during a time
| v | a 6x1 twist vector in (t utheta) notation |
| delta_t | the time during which the twist v is applied |
Definition at line 176 of file eigen_utils.cpp.
| double eigen_utils::f_mcosc | ( | double | cosx, |
| double | x | ||
| ) |
Definition at line 140 of file eigen_utils.cpp.
| double eigen_utils::f_msinc | ( | double | sinx, |
| double | x | ||
| ) |
Definition at line 146 of file eigen_utils.cpp.
| double eigen_utils::f_sinc | ( | double | sinx, |
| double | x | ||
| ) |
Definition at line 134 of file eigen_utils.cpp.
| bool eigen_utils::getTransform | ( | const tf::TransformListener & | listener, |
| const std::string & | target, | ||
| const std::string | source, | ||
| Eigen::Affine3d & | tMs, | ||
| const ros::Time & | timestamp = ros::Time::now(), |
||
| const ros::Duration & | timeout = ros::Duration(5.0) |
||
| ) |
Queries tf for a transform and returns it as an eigen affine3d object
| listener | the tf listener object | |
| target | the target frame name (t) | |
| source | the source frame name (s) | |
| [out] | tMs | an homogeneous matrix describing the source frame in target coordinates |
| timestamp | the desired timestamp | |
| timeout | the maximum time to wait for the transform |
Definition at line 221 of file eigen_utils.cpp.
| void eigen_utils::pseudoinverse | ( | const Eigen::MatrixXd & | M, |
| Eigen::MatrixXd & | Minv, | ||
| double | tolerance = 1.e-06 |
||
| ) |
Computes the pseudoinverse of a matrix via SVD
| M | the input matrix |
| Minv[out] | the output pseudoinverse matrix |
| tolerance | Those singular values smaller than tolerance * max_singular_value are removed |
Definition at line 39 of file eigen_utils.cpp.
| Eigen::MatrixXd eigen_utils::pseudoinverse | ( | const Eigen::MatrixXd & | M, |
| double | tolerance = 1.e-06 |
||
| ) |
Computes the pseudoinverse of a matrix via SVD
| M | the input matrix |
| tolerance | Those singular values smaller than tolerance * max_singular_value are removed |
Definition at line 61 of file eigen_utils.cpp.
| void eigen_utils::transformToPoseVector | ( | const Eigen::Affine3d & | M, |
| Eigen::VectorXd & | pose | ||
| ) |
Computes a pose vector in (t utheta) notation from an homogeneous transformation matrix
| M | an homogeneous transformation matrix |
| pose[out] | an output 6x1 vector containing the translation and rotation (utheta notation) described by matrix M |
Definition at line 68 of file eigen_utils.cpp.
| Eigen::VectorXd eigen_utils::transformToPoseVector | ( | const Eigen::Affine3d & | M | ) |
Computes a pose vector in (t utheta) notation from an homogeneous transformation matrix
| M | an homogeneous transformation matrix |
Definition at line 123 of file eigen_utils.cpp.
| Eigen::Affine3d eigen_utils::UThetaToAffine3d | ( | const Eigen::Vector3d & | u | ) |
Computes a rotation matrix corresponding to a utheta rotation
| u | a 3x1 vector containing a rotation in utheta notation |
Definition at line 152 of file eigen_utils.cpp.
const double eigen_utils::ang_min_mc = 2.5e-4 [static] |
Definition at line 132 of file eigen_utils.cpp.
const double eigen_utils::ang_min_sinc = 1.0e-8 [static] |
Definition at line 131 of file eigen_utils.cpp.