Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
exotica Namespace Reference

Namespaces

 visualization
 

Classes

class  AbstractDynamicsSolver
 
class  AbstractTimeIndexedProblem
 
class  AllowedCollisionMatrix
 
struct  AttachedObject
 
class  BoundedEndPoseProblem
 Bound constrained end-pose problem implementation. More...
 
class  BoundedTimeIndexedProblem
 Bound constrained time-indexed problem. More...
 
struct  BoxQPSolution
 
struct  CollisionProxy
 
class  CollisionScene
 The class of collision scene. More...
 
struct  ContinuousCollisionProxy
 
class  DynamicTimeIndexedShootingProblem
 
class  EndPoseProblem
 Arbitrarily constrained end-pose problem implementation. More...
 
struct  EndPoseTask
 
class  Exception
 
class  Factory
 Templated Object factory for Default-constructible classes. The Factory is itself a singleton. More...
 
class  FeedbackMotionSolver
 
struct  FunctorBase
 
class  Initializer
 
class  InitializerBase
 
class  Instantiable
 
class  InstantiableBase
 
class  KinematicElement
 
struct  KinematicFrame
 
struct  KinematicFrameRequest
 
struct  KinematicResponse
 The KinematicResponse is the container to keep kinematic update data. The corresponding KinematicSolution is created from and indexes into a KinematicResponse. More...
 
class  KinematicSolution
 The KinematicSolution is created from - and maps into - a KinematicResponse. More...
 
struct  KinematicsRequest
 
class  KinematicTree
 
class  MotionSolver
 
class  Object
 
class  PlanningProblem
 
class  Printable
 
class  Property
 
class  Registrar
 Registration Class for the object type: Also templated: More...
 
class  RosNode
 
class  SamplingProblem
 
struct  SamplingTask
 
class  Scene
 The class of EXOTica Scene. More...
 
class  Server
 
class  Setup
 
class  SolveException
 
struct  Task
 
struct  TaskIndexing
 
class  TaskMap
 
struct  TaskSpaceVector
 
struct  TaskVectorEntry
 
class  TestCout
 
class  TimeIndexedProblem
 Time-indexed problem with bound, joint velocity, and general equality/inequality constraints. More...
 
class  TimeIndexedSamplingProblem
 
struct  TimeIndexedTask
 
class  Timer
 
class  Trajectory
 
class  UnconstrainedEndPoseProblem
 
class  UnconstrainedTimeIndexedProblem
 Unconstrained time-indexed problem. More...
 
class  Uncopyable
 
class  VisualElement
 
class  VisualizationMeshcat
 
class  VisualizationMoveIt
 
class  XMLLoader
 

Typedefs

typedef Eigen::Array< KDL::Frame, Eigen::Dynamic, 1 > ArrayFrame
 
typedef Eigen::Ref< ArrayFrameArrayFrameRef
 
typedef Eigen::internal::ref_selector< ArrayFrame >::type ArrayFrameRefConst
 
typedef Eigen::Array< Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 >, Eigen::Dynamic, 1 > ArrayHessian
 
typedef Eigen::Ref< ArrayHessianArrayHessianRef
 
typedef Eigen::internal::ref_selector< ArrayHessian >::type ArrayHessianRefConst
 
typedef Eigen::Array< KDL::Jacobian, Eigen::Dynamic, 1 > ArrayJacobian
 
typedef Eigen::Ref< ArrayJacobianArrayJacobianRef
 
typedef Eigen::internal::ref_selector< ArrayJacobian >::type ArrayJacobianRefConst
 
typedef Eigen::Array< KDL::Twist, Eigen::Dynamic, 1 > ArrayTwist
 
typedef Eigen::Ref< ArrayTwistArrayTwistRef
 
typedef Eigen::internal::ref_selector< ArrayTwist >::type ArrayTwistRefConst
 
typedef std::shared_ptr< exotica::BoundedEndPoseProblemBoundedEndPoseProblemPtr
 
typedef std::shared_ptr< exotica::BoundedTimeIndexedProblemBoundedTimeIndexedProblemPtr
 
typedef struct exotica::BoxQPSolution BoxQPSolution
 
typedef std::shared_ptr< CollisionSceneCollisionScenePtr
 
typedef AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > DynamicsSolver
 
typedef std::shared_ptr< exotica::DynamicsSolverDynamicsSolverPtr
 
typedef std::shared_ptr< exotica::DynamicTimeIndexedShootingProblemDynamicTimeIndexedShootingProblemPtr
 
typedef std::shared_ptr< exotica::EndPoseProblemEndPoseProblemPtr
 
typedef FunctorBase< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic > Functor
 
typedef Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > Hessian
 
typedef Eigen::Ref< HessianHessianRef
 
typedef Eigen::internal::ref_selector< Hessian >::type HessianRefConst
 
typedef std::shared_ptr< exotica::MotionSolverMotionSolverPtr
 
typedef std::shared_ptr< const PlanningProblemPlanningProblemConstPtr
 
typedef Factory< PlanningProblemPlanningProblemFac
 
typedef std::shared_ptr< PlanningProblemPlanningProblemPtr
 
typedef std::shared_ptr< exotica::SamplingProblemSamplingProblemPtr
 
typedef std::shared_ptr< SceneScenePtr
 
typedef std::shared_ptr< ServerServerPtr
 
typedef std::shared_ptr< SetupSetupPtr
 
typedef std::map< std::string, TaskMapPtrTaskMapMap
 The mapping by name of TaskMaps. More...
 
typedef std::shared_ptr< TaskMapTaskMapPtr
 Task Map smart pointer. More...
 
typedef std::vector< TaskMapPtrTaskMapVec
 
typedef std::shared_ptr< exotica::TimeIndexedProblemTimeIndexedProblemPtr
 
typedef std::shared_ptr< exotica::TimeIndexedSamplingProblemTimeIndexedSamplingProblemPtr
 
typedef std::shared_ptr< exotica::UnconstrainedEndPoseProblemUnconstrainedEndPoseProblemPtr
 
typedef std::shared_ptr< exotica::UnconstrainedTimeIndexedProblemUnconstrainedTimeIndexedProblemPtr
 

Enumerations

enum  ArgumentPosition {
  ARG0 = 0, ARG1 = 1, ARG2 = 2, ARG3 = 3,
  ARG4 = 4
}
 Argument position. Used as parameter to refer to an argument. More...
 
enum  BaseType { FIXED = 0, FLOATING = 10, PLANAR = 20 }
 
enum  ControlCostLossTermType {
  Undefined = -1, L2 = 0, SmoothL1 = 1, Huber = 2,
  PseudoHuber = 3
}
 
enum  Integrator { RK1 = 0, SymplecticEuler, RK2, RK4 }
 
enum  JointLimitType { LIMIT_POSITION_LOWER = 0, LIMIT_POSITION_UPPER = 1 }
 
enum  KinematicRequestFlags { KIN_FK = 0, KIN_J = 2, KIN_FK_VEL = 4, KIN_H = 8 }
 
enum  RotationType {
  RotationType::QUATERNION, RotationType::RPY, RotationType::ZYX, RotationType::ZYZ,
  RotationType::ANGLE_AXIS, RotationType::MATRIX
}
 
enum  TerminationCriterion {
  TerminationCriterion::NotStarted = -1, TerminationCriterion::IterationLimit, TerminationCriterion::BacktrackIterationLimit, TerminationCriterion::StepTolerance,
  TerminationCriterion::FunctionTolerance, TerminationCriterion::GradientTolerance, TerminationCriterion::Divergence, TerminationCriterion::UserDefined,
  TerminationCriterion::Convergence
}
 

Functions

void appendChildXML (Initializer &parent, std::string &name, bool isAttribute, tinyxml2::XMLHandle &tag, const std::string &prefix)
 
void AppendInitializer (std::shared_ptr< InstantiableBase > it, std::vector< Initializer > &ret)
 
template<class Key , class Val >
void AppendMap (std::map< Key, Val > &orig, const std::map< Key, Val > &extra)
 
template<class Val >
void AppendVector (std::vector< Val > &orig, const std::vector< Val > &extra)
 
BoxQPSolution BoxQP (const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init)
 
BoxQPSolution BoxQP (const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init, const double th_acceptstep, const int max_iterations, const double th_gradient_tolerance, const double lambda, bool use_polynomial_linesearch=true, bool use_cholesky_factorization=true)
 
BoxQPSolution ExoticaBoxQP (const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init)
 
BoxQPSolution ExoticaBoxQP (const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init, const double gamma, const int max_iterations, const double epsilon, const double lambda, bool use_polynomial_linesearch=false, bool use_cholesky_factorization=false)
 
std_msgs::ColorRGBA GetColor (const Eigen::Vector4d &rgba)
 
std_msgs::ColorRGBA GetColor (double r, double g, double b, double a=1.0)
 
Eigen::MatrixXd GetFrame (const KDL::Frame &val)
 
KDL::Frame GetFrame (Eigen::VectorXdRefConst val)
 
Eigen::VectorXd GetFrameAsVector (const KDL::Frame &val, RotationType type=RotationType::RPY)
 
KDL::Frame GetFrameFromMatrix (Eigen::MatrixXdRefConst val)
 
template<typename T >
std::vector< std::string > GetKeys (std::map< std::string, T > map)
 
template<class Key , class Val >
std::vector< Key > GetKeysFromMap (const std::map< Key, Val > &map)
 
KDL::Rotation GetRotation (Eigen::VectorXdRefConst data, RotationType type)
 
Eigen::VectorXd GetRotationAsVector (const KDL::Frame &val, RotationType type)
 
RotationType GetRotationTypeFromString (const std::string &rotation_type)
 
int GetRotationTypeLength (const RotationType &type)
 
std::string GetTypeName (const std::type_info &type)
 
template<class Key , class Val >
std::vector< Val > GetValuesFromMap (const std::map< Key, Val > &map)
 
double huber_cost (double x, double beta)
 
double huber_hessian (double x, double beta)
 
double huber_jacobian (double x, double beta)
 
bool IsContainerType (std::string type)
 
bool IsRobotLink (std::shared_ptr< KinematicElement > e)
 
bool IsVectorContainerType (std::string type)
 
bool IsVectorType (std::string type)
 
std::string LoadFile (const std::string &path)
 
robot_model::RobotModelPtr LoadModelImpl (const std::string &urdf, const std::string &srdf)
 
void LoadOBJ (const std::string &data, Eigen::VectorXi &tri, Eigen::VectorXd &vert)
 LoadOBJ Loads mesh data from an OBJ file. More...
 
std::shared_ptr< octomap::OcTreeLoadOctree (const std::string &file_path)
 
std::shared_ptr< shapes::ShapeLoadOctreeAsShape (const std::string &file_path)
 
template<class Key , class Val >
std::vector< Val > MapToVec (const std::map< Key, Val > &map)
 
void NormalizeQuaternionInConfigurationVector (Eigen::Ref< Eigen::VectorXd > q)
 
KinematicRequestFlags operator& (KinematicRequestFlags a, KinematicRequestFlags b)
 
std::ostream & operator<< (std::ostream &os, const Printable &s)
 
template<typename I , typename T >
std::ostream & operator<< (std::ostream &os, const std::map< I, T > &s)
 
template<typename T >
std::ostream & operator<< (std::ostream &os, const std::vector< T > &s)
 
Exception::ReportingType operator| (Exception::ReportingType a, Exception::ReportingType b) noexcept
 
KinematicRequestFlags operator| (KinematicRequestFlags a, KinematicRequestFlags b)
 
bool ParseBool (const std::string value)
 
std::vector< bool > ParseBoolList (const std::string value)
 
double ParseDouble (const std::string value)
 
int ParseInt (const std::string value)
 
std::vector< int > ParseIntList (const std::string value)
 
std::vector< std::string > ParseList (const std::string &value, char token=',')
 
std::string ParsePath (const std::string &path)
 
template<typename T , const int S>
Eigen::Matrix< T, S, 1 > ParseVector (const std::string value)
 
bool parseXML (tinyxml2::XMLHandle &tag, Initializer &parent, const std::string &prefix)
 
bool PathExists (const std::string &path)
 
void PrintDimensions (const std::string &name, const Eigen::Ref< const Eigen::MatrixXd > m)
 
double pseudo_huber_cost (double x, double beta)
 
double pseudo_huber_hessian (double x, double beta)
 
double pseudo_huber_jacobian (double x, double beta)
 
std_msgs::ColorRGBA RandomColor ()
 RandomColor Generates random opaque color. More...
 
void SaveMatrix (std::string file_name, const Eigen::Ref< const Eigen::MatrixXd > mat)
 
void SetDefaultQuaternionInConfigurationVector (Eigen::Ref< Eigen::VectorXd > q)
 
Eigen::VectorXd SetRotation (const KDL::Rotation &data, RotationType type)
 
void Sleep (double t)
 
double smooth_l1_cost (double x, double beta)
 
double smooth_l1_hessian (double x, double beta)
 
double smooth_l1_jacobian (double x, double beta)
 
template<typename T >
ToNumber (const std::string &val)
 
template<>
double ToNumber< double > (const std::string &val)
 
template<>
float ToNumber< float > (const std::string &val)
 
template<>
int ToNumber< int > (const std::string &val)
 
std::string ToString (const Eigen::Isometry3d &s)
 
std::string ToString (const KDL::Frame &s)
 
std::string Trim (const std::string &s)
 

Variables

const char branch []
 
constexpr double inf = std::numeric_limits<double>::infinity()
 
constexpr double pi = M_PI
 
const char version []
 

Typedef Documentation

◆ ArrayFrame

typedef Eigen::Array<KDL::Frame, Eigen::Dynamic, 1> exotica::ArrayFrame

Definition at line 151 of file conversions.h.

◆ ArrayFrameRef

typedef Eigen::Ref<ArrayFrame> exotica::ArrayFrameRef

Definition at line 157 of file conversions.h.

◆ ArrayFrameRefConst

typedef Eigen::internal::ref_selector<ArrayFrame>::type exotica::ArrayFrameRefConst

Definition at line 163 of file conversions.h.

◆ ArrayHessian

typedef Eigen::Array<Eigen::Array<Eigen::MatrixXd, Eigen::Dynamic, 1>, Eigen::Dynamic, 1> exotica::ArrayHessian

Definition at line 155 of file conversions.h.

◆ ArrayHessianRef

Definition at line 161 of file conversions.h.

◆ ArrayHessianRefConst

typedef Eigen::internal::ref_selector<ArrayHessian>::type exotica::ArrayHessianRefConst

Definition at line 167 of file conversions.h.

◆ ArrayJacobian

typedef Eigen::Array<KDL::Jacobian, Eigen::Dynamic, 1> exotica::ArrayJacobian

Definition at line 153 of file conversions.h.

◆ ArrayJacobianRef

Definition at line 159 of file conversions.h.

◆ ArrayJacobianRefConst

typedef Eigen::internal::ref_selector<ArrayJacobian>::type exotica::ArrayJacobianRefConst

Definition at line 165 of file conversions.h.

◆ ArrayTwist

typedef Eigen::Array<KDL::Twist, Eigen::Dynamic, 1> exotica::ArrayTwist

Definition at line 152 of file conversions.h.

◆ ArrayTwistRef

typedef Eigen::Ref<ArrayTwist> exotica::ArrayTwistRef

Definition at line 158 of file conversions.h.

◆ ArrayTwistRefConst

typedef Eigen::internal::ref_selector<ArrayTwist>::type exotica::ArrayTwistRefConst

Definition at line 164 of file conversions.h.

◆ BoundedEndPoseProblemPtr

Definition at line 74 of file bounded_end_pose_problem.h.

◆ BoundedTimeIndexedProblemPtr

Definition at line 92 of file bounded_time_indexed_problem.h.

◆ BoxQPSolution

◆ CollisionScenePtr

typedef std::shared_ptr<CollisionScene> exotica::CollisionScenePtr

Definition at line 341 of file collision_scene.h.

◆ DynamicsSolver

typedef AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > exotica::DynamicsSolver

Definition at line 267 of file dynamics_solver.h.

◆ DynamicsSolverPtr

Definition at line 269 of file dynamics_solver.h.

◆ DynamicTimeIndexedShootingProblemPtr

Definition at line 231 of file dynamic_time_indexed_shooting_problem.h.

◆ EndPoseProblemPtr

Definition at line 88 of file end_pose_problem.h.

◆ Functor

typedef FunctorBase<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic> exotica::Functor

Definition at line 49 of file functor.h.

◆ Hessian

typedef Eigen::Array<Eigen::MatrixXd, Eigen::Dynamic, 1> exotica::Hessian

Definition at line 154 of file conversions.h.

◆ HessianRef

typedef Eigen::Ref<Hessian> exotica::HessianRef

Definition at line 160 of file conversions.h.

◆ HessianRefConst

typedef Eigen::internal::ref_selector<Hessian>::type exotica::HessianRefConst

Definition at line 166 of file conversions.h.

◆ MotionSolverPtr

Definition at line 66 of file motion_solver.h.

◆ PlanningProblemConstPtr

typedef std::shared_ptr<const PlanningProblem> exotica::PlanningProblemConstPtr

Definition at line 117 of file planning_problem.h.

◆ PlanningProblemFac

Definition at line 115 of file planning_problem.h.

◆ PlanningProblemPtr

typedef std::shared_ptr<PlanningProblem> exotica::PlanningProblemPtr

Definition at line 116 of file planning_problem.h.

◆ SamplingProblemPtr

Definition at line 83 of file sampling_problem.h.

◆ ScenePtr

typedef std::shared_ptr<Scene> exotica::ScenePtr

Definition at line 246 of file scene.h.

◆ ServerPtr

typedef std::shared_ptr<Server> exotica::ServerPtr

Definition at line 188 of file server.h.

◆ SetupPtr

typedef std::shared_ptr<Setup> exotica::SetupPtr

Definition at line 140 of file setup.h.

◆ TaskMapMap

typedef std::map<std::string, TaskMapPtr> exotica::TaskMapMap

The mapping by name of TaskMaps.

Definition at line 93 of file task_map.h.

◆ TaskMapPtr

typedef std::shared_ptr<TaskMap> exotica::TaskMapPtr

Task Map smart pointer.

Definition at line 92 of file task_map.h.

◆ TaskMapVec

typedef std::vector<TaskMapPtr> exotica::TaskMapVec

Definition at line 94 of file task_map.h.

◆ TimeIndexedProblemPtr

Definition at line 51 of file time_indexed_problem.h.

◆ TimeIndexedSamplingProblemPtr

Definition at line 89 of file time_indexed_sampling_problem.h.

◆ UnconstrainedEndPoseProblemPtr

Definition at line 82 of file unconstrained_end_pose_problem.h.

◆ UnconstrainedTimeIndexedProblemPtr

Definition at line 98 of file unconstrained_time_indexed_problem.h.

Enumeration Type Documentation

◆ ArgumentPosition

Argument position. Used as parameter to refer to an argument.

Enumerator
ARG0 
ARG1 
ARG2 
ARG3 
ARG4 

Definition at line 123 of file tools.h.

◆ BaseType

Enumerator
FIXED 
FLOATING 
PLANAR 

Definition at line 49 of file kinematic_tree.h.

◆ ControlCostLossTermType

Enumerator
Undefined 
L2 
SmoothL1 
Huber 
PseudoHuber 

Definition at line 41 of file dynamic_time_indexed_shooting_problem.h.

◆ Integrator

Enumerator
RK1 

Forward Euler (explicit)

SymplecticEuler 

Semi-Implicit Euler.

RK2 

Explicit trapezoid rule.

RK4 

Runge-Kutta 4.

Definition at line 46 of file dynamics_solver.h.

◆ JointLimitType

Enumerator
LIMIT_POSITION_LOWER 
LIMIT_POSITION_UPPER 

Definition at line 64 of file kinematic_tree.h.

◆ KinematicRequestFlags

Enumerator
KIN_FK 
KIN_J 
KIN_FK_VEL 
KIN_H 

Definition at line 56 of file kinematic_tree.h.

◆ RotationType

enum exotica::RotationType
strong
Enumerator
QUATERNION 
RPY 
ZYX 
ZYZ 
ANGLE_AXIS 
MATRIX 

Definition at line 79 of file conversions.h.

◆ TerminationCriterion

Enumerator
NotStarted 
IterationLimit 
BacktrackIterationLimit 
StepTolerance 
FunctionTolerance 
GradientTolerance 
Divergence 
UserDefined 
Convergence 

Definition at line 49 of file planning_problem.h.

Function Documentation

◆ appendChildXML()

void exotica::appendChildXML ( Initializer parent,
std::string &  name,
bool  isAttribute,
tinyxml2::XMLHandle &  tag,
const std::string &  prefix 
)

Definition at line 43 of file xml_loader.cpp.

◆ AppendInitializer()

void exotica::AppendInitializer ( std::shared_ptr< InstantiableBase it,
std::vector< Initializer > &  ret 
)

Definition at line 82 of file setup.cpp.

◆ AppendMap()

template<class Key , class Val >
void exotica::AppendMap ( std::map< Key, Val > &  orig,
const std::map< Key, Val > &  extra 
)

Definition at line 217 of file conversions.h.

◆ AppendVector()

template<class Val >
void exotica::AppendVector ( std::vector< Val > &  orig,
const std::vector< Val > &  extra 
)

Definition at line 223 of file conversions.h.

◆ BoxQP() [1/2]

BoxQPSolution exotica::BoxQP ( const Eigen::MatrixXd &  H,
const Eigen::VectorXd q,
const Eigen::VectorXd b_low,
const Eigen::VectorXd b_high,
const Eigen::VectorXd x_init 
)
inline

Definition at line 261 of file box_qp.h.

◆ BoxQP() [2/2]

BoxQPSolution exotica::BoxQP ( const Eigen::MatrixXd &  H,
const Eigen::VectorXd q,
const Eigen::VectorXd b_low,
const Eigen::VectorXd b_high,
const Eigen::VectorXd x_init,
const double  th_acceptstep,
const int  max_iterations,
const double  th_gradient_tolerance,
const double  lambda,
bool  use_polynomial_linesearch = true,
bool  use_cholesky_factorization = true 
)
inline

Definition at line 47 of file box_qp.h.

◆ ExoticaBoxQP() [1/2]

BoxQPSolution exotica::ExoticaBoxQP ( const Eigen::MatrixXd &  H,
const Eigen::VectorXd q,
const Eigen::VectorXd b_low,
const Eigen::VectorXd b_high,
const Eigen::VectorXd x_init 
)
inline

Definition at line 185 of file box_qp_old.h.

◆ ExoticaBoxQP() [2/2]

BoxQPSolution exotica::ExoticaBoxQP ( const Eigen::MatrixXd &  H,
const Eigen::VectorXd q,
const Eigen::VectorXd b_low,
const Eigen::VectorXd b_high,
const Eigen::VectorXd x_init,
const double  gamma,
const int  max_iterations,
const double  epsilon,
const double  lambda,
bool  use_polynomial_linesearch = false,
bool  use_cholesky_factorization = false 
)
inline

Definition at line 40 of file box_qp_old.h.

◆ GetColor() [1/2]

std_msgs::ColorRGBA exotica::GetColor ( const Eigen::Vector4d &  rgba)
inline

Definition at line 79 of file tools.h.

◆ GetColor() [2/2]

std_msgs::ColorRGBA exotica::GetColor ( double  r,
double  g,
double  b,
double  a = 1.0 
)
inline

Definition at line 69 of file tools.h.

◆ GetFrame() [1/2]

Eigen::MatrixXd exotica::GetFrame ( const KDL::Frame &  val)

Definition at line 91 of file conversions.cpp.

◆ GetFrame() [2/2]

KDL::Frame exotica::GetFrame ( Eigen::VectorXdRefConst  val)

Definition at line 52 of file conversions.cpp.

◆ GetFrameAsVector()

Eigen::VectorXd exotica::GetFrameAsVector ( const KDL::Frame &  val,
RotationType  type = RotationType::RPY 
)

Definition at line 98 of file conversions.cpp.

◆ GetFrameFromMatrix()

KDL::Frame exotica::GetFrameFromMatrix ( Eigen::MatrixXdRefConst  val)

Definition at line 71 of file conversions.cpp.

◆ GetKeys()

template<typename T >
std::vector<std::string> exotica::GetKeys ( std::map< std::string, T >  map)

Definition at line 106 of file tools.h.

◆ GetKeysFromMap()

template<class Key , class Val >
std::vector<Key> exotica::GetKeysFromMap ( const std::map< Key, Val > &  map)

Definition at line 195 of file conversions.h.

◆ GetRotation()

KDL::Rotation exotica::GetRotation ( Eigen::VectorXdRefConst  data,
RotationType  type 
)

Definition at line 114 of file conversions.cpp.

◆ GetRotationAsVector()

Eigen::VectorXd exotica::GetRotationAsVector ( const KDL::Frame &  val,
RotationType  type 
)

Definition at line 109 of file conversions.cpp.

◆ GetRotationTypeFromString()

RotationType exotica::GetRotationTypeFromString ( const std::string &  rotation_type)
inline

Definition at line 99 of file conversions.h.

◆ GetRotationTypeLength()

int exotica::GetRotationTypeLength ( const RotationType type)
inline

Definition at line 93 of file conversions.h.

◆ GetTypeName()

std::string exotica::GetTypeName ( const std::type_info &  type)

< We need to store this to free the memory!

< We need to store this to free the memory!

Definition at line 133 of file tools.cpp.

◆ GetValuesFromMap()

template<class Key , class Val >
std::vector<Val> exotica::GetValuesFromMap ( const std::map< Key, Val > &  map)

Definition at line 206 of file conversions.h.

◆ huber_cost()

double exotica::huber_cost ( double  x,
double  beta 
)
inline

Definition at line 39 of file sparse_costs.h.

◆ huber_hessian()

double exotica::huber_hessian ( double  x,
double  beta 
)
inline

Definition at line 56 of file sparse_costs.h.

◆ huber_jacobian()

double exotica::huber_jacobian ( double  x,
double  beta 
)
inline

Definition at line 47 of file sparse_costs.h.

◆ IsContainerType()

bool exotica::IsContainerType ( std::string  type)
inline

Definition at line 169 of file conversions.h.

◆ IsRobotLink()

bool exotica::IsRobotLink ( std::shared_ptr< KinematicElement e)
inline

Definition at line 37 of file collision_scene.cpp.

◆ IsVectorContainerType()

bool exotica::IsVectorContainerType ( std::string  type)
inline

Definition at line 179 of file conversions.h.

◆ IsVectorType()

bool exotica::IsVectorType ( std::string  type)
inline

Definition at line 174 of file conversions.h.

◆ LoadFile()

std::string exotica::LoadFile ( const std::string &  path)

Definition at line 184 of file tools.cpp.

◆ LoadModelImpl()

robot_model::RobotModelPtr exotica::LoadModelImpl ( const std::string &  urdf,
const std::string &  srdf 
)

Definition at line 62 of file server.cpp.

◆ LoadOBJ()

void exotica::LoadOBJ ( const std::string &  data,
Eigen::VectorXi &  tri,
Eigen::VectorXd vert 
)

LoadOBJ Loads mesh data from an OBJ file.

Parameters
file_nameFile name
triReturned vertex indices of triangles
vertVertex positions

Definition at line 75 of file tools.cpp.

◆ LoadOctree()

std::shared_ptr< octomap::OcTree > exotica::LoadOctree ( const std::string &  file_path)

Definition at line 119 of file tools.cpp.

◆ LoadOctreeAsShape()

std::shared_ptr< shapes::Shape > exotica::LoadOctreeAsShape ( const std::string &  file_path)

Definition at line 126 of file tools.cpp.

◆ MapToVec()

template<class Key , class Val >
std::vector<Val> exotica::MapToVec ( const std::map< Key, Val > &  map)

Definition at line 185 of file conversions.h.

◆ NormalizeQuaternionInConfigurationVector()

void exotica::NormalizeQuaternionInConfigurationVector ( Eigen::Ref< Eigen::VectorXd q)
inline

Definition at line 141 of file conversions.h.

◆ operator&()

KinematicRequestFlags exotica::operator& ( KinematicRequestFlags  a,
KinematicRequestFlags  b 
)
inline

Definition at line 78 of file kinematic_tree.h.

◆ operator<<() [1/3]

std::ostream & exotica::operator<< ( std::ostream &  os,
const Printable s 
)

Definition at line 34 of file printable.cpp.

◆ operator<<() [2/3]

template<typename I , typename T >
std::ostream& exotica::operator<< ( std::ostream &  os,
const std::map< I, T > &  s 
)

Definition at line 85 of file printable.h.

◆ operator<<() [3/3]

template<typename T >
std::ostream& exotica::operator<< ( std::ostream &  os,
const std::vector< T > &  s 
)

Definition at line 78 of file printable.h.

◆ operator|() [1/2]

Exception::ReportingType exotica::operator| ( Exception::ReportingType  a,
Exception::ReportingType  b 
)
inlinenoexcept

Definition at line 72 of file exception.h.

◆ operator|() [2/2]

KinematicRequestFlags exotica::operator| ( KinematicRequestFlags  a,
KinematicRequestFlags  b 
)
inline

Definition at line 73 of file kinematic_tree.h.

◆ ParseBool()

bool exotica::ParseBool ( const std::string  value)
inline

Definition at line 287 of file conversions.h.

◆ ParseBoolList()

std::vector<bool> exotica::ParseBoolList ( const std::string  value)
inline

Definition at line 354 of file conversions.h.

◆ ParseDouble()

double exotica::ParseDouble ( const std::string  value)
inline

Definition at line 295 of file conversions.h.

◆ ParseInt()

int exotica::ParseInt ( const std::string  value)
inline

Definition at line 308 of file conversions.h.

◆ ParseIntList()

std::vector<int> exotica::ParseIntList ( const std::string  value)
inline

Definition at line 334 of file conversions.h.

◆ ParseList()

std::vector<std::string> exotica::ParseList ( const std::string &  value,
char  token = ',' 
)
inline

Definition at line 321 of file conversions.h.

◆ ParsePath()

std::string exotica::ParsePath ( const std::string &  path)

Definition at line 145 of file tools.cpp.

◆ ParseVector()

template<typename T , const int S>
Eigen::Matrix<T, S, 1> exotica::ParseVector ( const std::string  value)
inline

Definition at line 259 of file conversions.h.

◆ parseXML()

bool exotica::parseXML ( tinyxml2::XMLHandle &  tag,
Initializer parent,
const std::string &  prefix 
)

Definition at line 98 of file xml_loader.cpp.

◆ PathExists()

bool exotica::PathExists ( const std::string &  path)

Definition at line 199 of file tools.cpp.

◆ PrintDimensions()

void exotica::PrintDimensions ( const std::string &  name,
const Eigen::Ref< const Eigen::MatrixXd >  m 
)

Definition at line 53 of file printable.cpp.

◆ pseudo_huber_cost()

double exotica::pseudo_huber_cost ( double  x,
double  beta 
)
inline

Definition at line 86 of file sparse_costs.h.

◆ pseudo_huber_hessian()

double exotica::pseudo_huber_hessian ( double  x,
double  beta 
)
inline

Definition at line 96 of file sparse_costs.h.

◆ pseudo_huber_jacobian()

double exotica::pseudo_huber_jacobian ( double  x,
double  beta 
)
inline

Definition at line 91 of file sparse_costs.h.

◆ RandomColor()

std_msgs::ColorRGBA exotica::RandomColor ( )

RandomColor Generates random opaque color.

Returns
Random color

Definition at line 45 of file tools.cpp.

◆ SaveMatrix()

void exotica::SaveMatrix ( std::string  file_name,
const Eigen::Ref< const Eigen::MatrixXd >  mat 
)

Definition at line 58 of file tools.cpp.

◆ SetDefaultQuaternionInConfigurationVector()

void exotica::SetDefaultQuaternionInConfigurationVector ( Eigen::Ref< Eigen::VectorXd q)
inline

Definition at line 146 of file conversions.h.

◆ SetRotation()

Eigen::VectorXd exotica::SetRotation ( const KDL::Rotation &  data,
RotationType  type 
)

Definition at line 150 of file conversions.cpp.

◆ Sleep()

void exotica::Sleep ( double  t)
inline

Definition at line 38 of file timer.h.

◆ smooth_l1_cost()

double exotica::smooth_l1_cost ( double  x,
double  beta 
)
inline

Definition at line 63 of file sparse_costs.h.

◆ smooth_l1_hessian()

double exotica::smooth_l1_hessian ( double  x,
double  beta 
)
inline

Definition at line 79 of file sparse_costs.h.

◆ smooth_l1_jacobian()

double exotica::smooth_l1_jacobian ( double  x,
double  beta 
)
inline

Definition at line 70 of file sparse_costs.h.

◆ ToNumber()

template<typename T >
T exotica::ToNumber ( const std::string &  val)

Definition at line 235 of file conversions.h.

◆ ToNumber< double >()

template<>
double exotica::ToNumber< double > ( const std::string &  val)
inline

Definition at line 247 of file conversions.h.

◆ ToNumber< float >()

template<>
float exotica::ToNumber< float > ( const std::string &  val)
inline

Definition at line 241 of file conversions.h.

◆ ToNumber< int >()

template<>
int exotica::ToNumber< int > ( const std::string &  val)
inline

Definition at line 253 of file conversions.h.

◆ ToString() [1/2]

std::string exotica::ToString ( const Eigen::Isometry3d &  s)

Definition at line 47 of file printable.cpp.

◆ ToString() [2/2]

std::string exotica::ToString ( const KDL::Frame &  s)

Definition at line 40 of file printable.cpp.

◆ Trim()

std::string exotica::Trim ( const std::string &  s)
inline

Definition at line 228 of file conversions.h.

Variable Documentation

◆ branch

const char exotica::branch[]

◆ inf

constexpr double exotica::inf = std::numeric_limits<double>::infinity()
constexpr

Definition at line 70 of file kinematic_tree.h.

◆ pi

constexpr double exotica::pi = M_PI
constexpr

Definition at line 71 of file kinematic_tree.h.

◆ version

const char exotica::version[]


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Fri Oct 20 2023 02:59:49