Gazebo Math

API Reference

6.15.1
gz/math/eigen3/Conversions.hh File Reference
#include <Eigen/Geometry>
#include <gz/math/AxisAlignedBox.hh>
#include <gz/math/Matrix3.hh>
#include <gz/math/Matrix6.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>

Go to the source code of this file.

Namespaces

 ignition
 
 ignition::math
 Math classes and function useful in robot applications.
 
 ignition::math::eigen3
 

Functions

Eigen::AlignedBox3d convert (const AxisAlignedBox &_b)
 Convert from AxisAlignedBox to Eigen::AlignedBox3d. More...
 
AxisAlignedBox convert (const Eigen::AlignedBox3d &_b)
 Convert Eigen::AlignedBox3d to AxisAlignedBox. More...
 
Pose3d convert (const Eigen::Isometry3d &_tf)
 Convert Eigen::Isometry3d to Pose3d. More...
 
Matrix3d convert (const Eigen::Matrix3d &_m)
 Convert Eigen::Matrix3d to Matrix3d. More...
 
template<typename Precision >
Matrix6< Precision > convert (const Eigen::Matrix< Precision, 6, 6 > &_m)
 Convert Eigen::Matrix<Precision, 6, 6> to Matrix6d. More...
 
Quaterniond convert (const Eigen::Quaterniond &_q)
 Convert Eigen::Quaterniond to Quaterniond. More...
 
Vector3d convert (const Eigen::Vector3d &_v)
 Convert Eigen::Vector3d to Vector3d. More...
 
Eigen::Matrix3d convert (const Matrix3d &_m)
 Convert from Matrix3d to Eigen::Matrix3d. More...
 
template<typename Precision >
Eigen::Matrix< Precision, 6, 6 > convert (const Matrix6< Precision > &_m)
 Convert from Matrix6d to Eigen::Matrix<Precision, 6, 6>. More...
 
Eigen::Isometry3d convert (const Pose3d &_pose)
 Convert Pose3d to Eigen::Isometry3d. More...
 
Eigen::Quaterniond convert (const Quaterniond &_q)
 Convert Quaterniond to Eigen::Quaterniond. More...
 
Eigen::Vector3d convert (const Vector3d &_v)
 Convert from Vector3d to Eigen::Vector3d. More...