Namespaces | Typedefs | Enumerations | Functions
conversions.h File Reference
#include <map>
#include <memory>
#include <vector>
#include <kdl/frames.hpp>
#include <kdl/jacobian.hpp>
#include <Eigen/Dense>
#include <unsupported/Eigen/CXX11/Tensor>
#include <exotica_core/tools/exception.h>
#include <exotica_core/tools/printable.h>
Include dependency graph for conversions.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 Eigen
 
 exotica
 

Typedefs

typedef Eigen::Array< KDL::Frame, Eigen::Dynamic, 1 > exotica::ArrayFrame
 
typedef Eigen::Ref< ArrayFrame > exotica::ArrayFrameRef
 
typedef Eigen::internal::ref_selector< ArrayFrame >::type exotica::ArrayFrameRefConst
 
typedef Eigen::Array< Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > exotica::ArrayHessian
 
typedef Eigen::Ref< ArrayHessian > exotica::ArrayHessianRef
 
typedef Eigen::internal::ref_selector< ArrayHessian >::type exotica::ArrayHessianRefConst
 
typedef Eigen::Array< KDL::Jacobian, Eigen::Dynamic, 1 > exotica::ArrayJacobian
 
typedef Eigen::Ref< ArrayJacobian > exotica::ArrayJacobianRef
 
typedef Eigen::internal::ref_selector< ArrayJacobian >::type exotica::ArrayJacobianRefConst
 
typedef Eigen::Array< KDL::Twist, Eigen::Dynamic, 1 > exotica::ArrayTwist
 
typedef Eigen::Ref< ArrayTwist > exotica::ArrayTwistRef
 
typedef Eigen::internal::ref_selector< ArrayTwist >::type exotica::ArrayTwistRefConst
 
typedef Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > exotica::Hessian
 
typedef Eigen::Ref< Hessian > exotica::HessianRef
 
typedef Eigen::internal::ref_selector< Hessian >::type exotica::HessianRefConst
 
template<typename T >
using Eigen::MatrixType = Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic >
 
typedef Eigen::Ref< Eigen::MatrixXd > Eigen::MatrixXdRef
 
typedef const Eigen::Ref< const Eigen::MatrixXd > & Eigen::MatrixXdRefConst
 
typedef Eigen::Ref< Eigen::VectorXd > Eigen::VectorXdRef
 
typedef const Eigen::Ref< const Eigen::VectorXd > & Eigen::VectorXdRefConst
 Convenience wrapper for storing references to sub-matrices/vectors. More...
 

Enumerations

enum  exotica::RotationType {
  exotica::RotationType::QUATERNION, exotica::RotationType::RPY, exotica::RotationType::ZYX, exotica::RotationType::ZYZ,
  exotica::RotationType::ANGLE_AXIS, exotica::RotationType::MATRIX
}
 

Functions

template<class Key , class Val >
void exotica::AppendMap (std::map< Key, Val > &orig, const std::map< Key, Val > &extra)
 
template<class Val >
void exotica::AppendVector (std::vector< Val > &orig, const std::vector< Val > &extra)
 
KDL::Frame exotica::GetFrame (Eigen::VectorXdRefConst val)
 
Eigen::MatrixXd exotica::GetFrame (const KDL::Frame &val)
 
Eigen::VectorXd exotica::GetFrameAsVector (const KDL::Frame &val, RotationType type=RotationType::RPY)
 
KDL::Frame exotica::GetFrameFromMatrix (Eigen::MatrixXdRefConst val)
 
template<class Key , class Val >
std::vector< Key > exotica::GetKeysFromMap (const std::map< Key, Val > &map)
 
KDL::Rotation exotica::GetRotation (Eigen::VectorXdRefConst data, RotationType type)
 
Eigen::VectorXd exotica::GetRotationAsVector (const KDL::Frame &val, RotationType type)
 
RotationType exotica::GetRotationTypeFromString (const std::string &rotation_type)
 
int exotica::GetRotationTypeLength (const RotationType &type)
 
template<class Key , class Val >
std::vector< Val > exotica::GetValuesFromMap (const std::map< Key, Val > &map)
 
Eigen::VectorXd Eigen::IdentityTransform ()
 
bool exotica::IsContainerType (std::string type)
 
bool exotica::IsVectorContainerType (std::string type)
 
bool exotica::IsVectorType (std::string type)
 
template<class Key , class Val >
std::vector< Val > exotica::MapToVec (const std::map< Key, Val > &map)
 
template<typename Scalar , typename... Dims>
Eigen::Tensor< Scalar, sizeof...(Dims)> Eigen::MatrixToTensor (const MatrixType< Scalar > &matrix, Dims...dims)
 
void exotica::NormalizeQuaternionInConfigurationVector (Eigen::Ref< Eigen::VectorXd > q)
 
bool exotica::ParseBool (const std::string value)
 
std::vector< bool > exotica::ParseBoolList (const std::string value)
 
double exotica::ParseDouble (const std::string value)
 
int exotica::ParseInt (const std::string value)
 
std::vector< int > exotica::ParseIntList (const std::string value)
 
std::vector< std::string > exotica::ParseList (const std::string &value, char token= ',')
 
template<typename T , const int S>
Eigen::Matrix< T, S, 1 > exotica::ParseVector (const std::string value)
 
void exotica::SetDefaultQuaternionInConfigurationVector (Eigen::Ref< Eigen::VectorXd > q)
 
Eigen::VectorXd exotica::SetRotation (const KDL::Rotation &data, RotationType type)
 
template<typename Scalar , int rank, typename sizeType >
MatrixType< Scalar > Eigen::TensorToMatrix (const Eigen::Tensor< Scalar, rank > &tensor, const sizeType rows, const sizeType cols)
 
template<typename T >
exotica::ToNumber (const std::string &val)
 
template<>
double exotica::ToNumber< double > (const std::string &val)
 
template<>
float exotica::ToNumber< float > (const std::string &val)
 
template<>
int exotica::ToNumber< int > (const std::string &val)
 
std::string exotica::Trim (const std::string &s)
 
Eigen::VectorXd Eigen::VectorTransform (double px=0.0, double py=0.0, double pz=0.0, double qx=0.0, double qy=0.0, double qz=0.0, double qw=1.0)
 


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:49