Namespaces | |
| visualization | |
Classes | |
| class | AbstractDynamicsSolver |
| class | AbstractTimeIndexedProblem |
| class | AllowedCollisionMatrix |
| The AllowedCollisionMatrix is a data structure containing links for which a detected collision does not result in a state to be considered invalid/in-collision. This can exclude links that are in collision by default, neighbouring links, or links that could never be possibly in collision (e.g. if out of reach). More... | |
| 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< ArrayFrame > | ArrayFrameRef |
| 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< ArrayHessian > | ArrayHessianRef |
| typedef Eigen::internal::ref_selector< ArrayHessian >::type | ArrayHessianRefConst |
| typedef Eigen::Array< KDL::Jacobian, Eigen::Dynamic, 1 > | ArrayJacobian |
| typedef Eigen::Ref< ArrayJacobian > | ArrayJacobianRef |
| typedef Eigen::internal::ref_selector< ArrayJacobian >::type | ArrayJacobianRefConst |
| typedef Eigen::Array< KDL::Twist, Eigen::Dynamic, 1 > | ArrayTwist |
| typedef Eigen::Ref< ArrayTwist > | ArrayTwistRef |
| typedef Eigen::internal::ref_selector< ArrayTwist >::type | ArrayTwistRefConst |
| typedef std::shared_ptr< exotica::BoundedEndPoseProblem > | BoundedEndPoseProblemPtr |
| typedef std::shared_ptr< exotica::BoundedTimeIndexedProblem > | BoundedTimeIndexedProblemPtr |
| typedef struct exotica::BoxQPSolution | BoxQPSolution |
| typedef std::shared_ptr< CollisionScene > | CollisionScenePtr |
| typedef AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > | DynamicsSolver |
| typedef std::shared_ptr< exotica::DynamicsSolver > | DynamicsSolverPtr |
| typedef std::shared_ptr< exotica::DynamicTimeIndexedShootingProblem > | DynamicTimeIndexedShootingProblemPtr |
| typedef std::shared_ptr< exotica::EndPoseProblem > | EndPoseProblemPtr |
| typedef FunctorBase< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic > | Functor |
| typedef Eigen::Array< Eigen::MatrixXd, Eigen::Dynamic, 1 > | Hessian |
| typedef Eigen::Ref< Hessian > | HessianRef |
| typedef Eigen::internal::ref_selector< Hessian >::type | HessianRefConst |
| typedef std::shared_ptr< exotica::MotionSolver > | MotionSolverPtr |
| typedef std::shared_ptr< const PlanningProblem > | PlanningProblemConstPtr |
| typedef Factory< PlanningProblem > | PlanningProblemFac |
| typedef std::shared_ptr< PlanningProblem > | PlanningProblemPtr |
| typedef std::shared_ptr< exotica::SamplingProblem > | SamplingProblemPtr |
| typedef std::shared_ptr< Scene > | ScenePtr |
| typedef std::shared_ptr< Server > | ServerPtr |
| typedef std::shared_ptr< Setup > | SetupPtr |
| typedef std::map< std::string, TaskMapPtr > | TaskMapMap |
| The mapping by name of TaskMaps. More... | |
| typedef std::shared_ptr< TaskMap > | TaskMapPtr |
| Task Map smart pointer. More... | |
| typedef std::vector< TaskMapPtr > | TaskMapVec |
| typedef std::shared_ptr< exotica::TimeIndexedProblem > | TimeIndexedProblemPtr |
| typedef std::shared_ptr< exotica::TimeIndexedSamplingProblem > | TimeIndexedSamplingProblemPtr |
| typedef std::shared_ptr< exotica::UnconstrainedEndPoseProblem > | UnconstrainedEndPoseProblemPtr |
| typedef std::shared_ptr< exotica::UnconstrainedTimeIndexedProblem > | UnconstrainedTimeIndexedProblemPtr |
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::OcTree > | LoadOctree (const std::string &file_path) |
| std::shared_ptr< shapes::Shape > | LoadOctreeAsShape (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 > | |
| T | ToNumber (const std::string &) |
| 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 = 1e20 |
| constexpr double | pi = M_PI |
| const char | version [] |
| typedef Eigen::Array<KDL::Frame, Eigen::Dynamic, 1> exotica::ArrayFrame |
Definition at line 152 of file conversions.h.
| typedef Eigen::Ref<ArrayFrame> exotica::ArrayFrameRef |
Definition at line 158 of file conversions.h.
| typedef Eigen::internal::ref_selector<ArrayFrame>::type exotica::ArrayFrameRefConst |
Definition at line 164 of file conversions.h.
| typedef Eigen::Array<Eigen::Array<Eigen::MatrixXd, Eigen::Dynamic, 1>, Eigen::Dynamic, 1> exotica::ArrayHessian |
Definition at line 156 of file conversions.h.
| typedef Eigen::Ref<ArrayHessian> exotica::ArrayHessianRef |
Definition at line 162 of file conversions.h.
| typedef Eigen::internal::ref_selector<ArrayHessian>::type exotica::ArrayHessianRefConst |
Definition at line 168 of file conversions.h.
| typedef Eigen::Array<KDL::Jacobian, Eigen::Dynamic, 1> exotica::ArrayJacobian |
Definition at line 154 of file conversions.h.
| typedef Eigen::Ref<ArrayJacobian> exotica::ArrayJacobianRef |
Definition at line 160 of file conversions.h.
| typedef Eigen::internal::ref_selector<ArrayJacobian>::type exotica::ArrayJacobianRefConst |
Definition at line 166 of file conversions.h.
| typedef Eigen::Array<KDL::Twist, Eigen::Dynamic, 1> exotica::ArrayTwist |
Definition at line 153 of file conversions.h.
| typedef Eigen::Ref<ArrayTwist> exotica::ArrayTwistRef |
Definition at line 159 of file conversions.h.
| typedef Eigen::internal::ref_selector<ArrayTwist>::type exotica::ArrayTwistRefConst |
Definition at line 165 of file conversions.h.
| typedef std::shared_ptr<exotica::BoundedEndPoseProblem> exotica::BoundedEndPoseProblemPtr |
Definition at line 74 of file bounded_end_pose_problem.h.
| typedef std::shared_ptr<exotica::BoundedTimeIndexedProblem> exotica::BoundedTimeIndexedProblemPtr |
Definition at line 92 of file bounded_time_indexed_problem.h.
| typedef struct exotica::BoxQPSolution exotica::BoxQPSolution |
| typedef std::shared_ptr<CollisionScene> exotica::CollisionScenePtr |
Definition at line 345 of file collision_scene.h.
| typedef AbstractDynamicsSolver< double, Eigen::Dynamic, Eigen::Dynamic > exotica::DynamicsSolver |
Definition at line 267 of file dynamics_solver.h.
| typedef std::shared_ptr<exotica::DynamicsSolver> exotica::DynamicsSolverPtr |
Definition at line 269 of file dynamics_solver.h.
| typedef std::shared_ptr<exotica::DynamicTimeIndexedShootingProblem> exotica::DynamicTimeIndexedShootingProblemPtr |
Definition at line 231 of file dynamic_time_indexed_shooting_problem.h.
| typedef std::shared_ptr<exotica::EndPoseProblem> exotica::EndPoseProblemPtr |
Definition at line 88 of file end_pose_problem.h.
| typedef FunctorBase<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::Dynamic> exotica::Functor |
| typedef Eigen::Array<Eigen::MatrixXd, Eigen::Dynamic, 1> exotica::Hessian |
Definition at line 155 of file conversions.h.
| typedef Eigen::Ref<Hessian> exotica::HessianRef |
Definition at line 161 of file conversions.h.
| typedef Eigen::internal::ref_selector<Hessian>::type exotica::HessianRefConst |
Definition at line 167 of file conversions.h.
| typedef std::shared_ptr<exotica::MotionSolver> exotica::MotionSolverPtr |
Definition at line 66 of file motion_solver.h.
| typedef std::shared_ptr<const PlanningProblem> exotica::PlanningProblemConstPtr |
Definition at line 117 of file planning_problem.h.
Definition at line 115 of file planning_problem.h.
| typedef std::shared_ptr<PlanningProblem> exotica::PlanningProblemPtr |
Definition at line 116 of file planning_problem.h.
| typedef std::shared_ptr<exotica::SamplingProblem> exotica::SamplingProblemPtr |
Definition at line 83 of file sampling_problem.h.
| typedef std::shared_ptr<Scene> exotica::ScenePtr |
| typedef std::shared_ptr<Server> exotica::ServerPtr |
| typedef std::shared_ptr<Setup> exotica::SetupPtr |
| typedef std::map<std::string, TaskMapPtr> exotica::TaskMapMap |
The mapping by name of TaskMaps.
Definition at line 93 of file task_map.h.
| typedef std::shared_ptr<TaskMap> exotica::TaskMapPtr |
Task Map smart pointer.
Definition at line 92 of file task_map.h.
| typedef std::vector<TaskMapPtr> exotica::TaskMapVec |
Definition at line 94 of file task_map.h.
| typedef std::shared_ptr<exotica::TimeIndexedProblem> exotica::TimeIndexedProblemPtr |
Definition at line 51 of file time_indexed_problem.h.
| typedef std::shared_ptr<exotica::TimeIndexedSamplingProblem> exotica::TimeIndexedSamplingProblemPtr |
Definition at line 88 of file time_indexed_sampling_problem.h.
| typedef std::shared_ptr<exotica::UnconstrainedEndPoseProblem> exotica::UnconstrainedEndPoseProblemPtr |
Definition at line 82 of file unconstrained_end_pose_problem.h.
| typedef std::shared_ptr<exotica::UnconstrainedTimeIndexedProblem> exotica::UnconstrainedTimeIndexedProblemPtr |
Definition at line 98 of file unconstrained_time_indexed_problem.h.
| enum exotica::BaseType |
| Enumerator | |
|---|---|
| FIXED | |
| FLOATING | |
| PLANAR | |
Definition at line 49 of file kinematic_tree.h.
| Enumerator | |
|---|---|
| Undefined | |
| L2 | |
| SmoothL1 | |
| Huber | |
| PseudoHuber | |
Definition at line 41 of file dynamic_time_indexed_shooting_problem.h.
| enum exotica::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.
| Enumerator | |
|---|---|
| LIMIT_POSITION_LOWER | |
| LIMIT_POSITION_UPPER | |
Definition at line 64 of file kinematic_tree.h.
| Enumerator | |
|---|---|
| KIN_FK | |
| KIN_J | |
| KIN_FK_VEL | |
| KIN_H | |
Definition at line 56 of file kinematic_tree.h.
|
strong |
| Enumerator | |
|---|---|
| QUATERNION | |
| RPY | |
| ZYX | |
| ZYZ | |
| ANGLE_AXIS | |
| MATRIX | |
Definition at line 80 of file conversions.h.
|
strong |
| Enumerator | |
|---|---|
| NotStarted | |
| IterationLimit | |
| BacktrackIterationLimit | |
| StepTolerance | |
| FunctionTolerance | |
| GradientTolerance | |
| Divergence | |
| UserDefined | |
| Convergence | |
Definition at line 49 of file planning_problem.h.
| 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.
| void exotica::AppendInitializer | ( | std::shared_ptr< InstantiableBase > | it, |
| std::vector< Initializer > & | ret | ||
| ) |
| void exotica::AppendMap | ( | std::map< Key, Val > & | orig, |
| const std::map< Key, Val > & | extra | ||
| ) |
Definition at line 218 of file conversions.h.
| void exotica::AppendVector | ( | std::vector< Val > & | orig, |
| const std::vector< Val > & | extra | ||
| ) |
Definition at line 224 of file conversions.h.
|
inline |
|
inline |
|
inline |
Definition at line 185 of file box_qp_old.h.
|
inline |
Definition at line 40 of file box_qp_old.h.
|
inline |
|
inline |
| Eigen::MatrixXd exotica::GetFrame | ( | const KDL::Frame & | val | ) |
Definition at line 91 of file conversions.cpp.
| KDL::Frame exotica::GetFrame | ( | Eigen::VectorXdRefConst | val | ) |
Definition at line 52 of file conversions.cpp.
| Eigen::VectorXd exotica::GetFrameAsVector | ( | const KDL::Frame & | val, |
| RotationType | type = RotationType::RPY |
||
| ) |
Definition at line 98 of file conversions.cpp.
| KDL::Frame exotica::GetFrameFromMatrix | ( | Eigen::MatrixXdRefConst | val | ) |
Definition at line 71 of file conversions.cpp.
| std::vector<std::string> exotica::GetKeys | ( | std::map< std::string, T > | map | ) |
| std::vector<Key> exotica::GetKeysFromMap | ( | const std::map< Key, Val > & | map | ) |
Definition at line 196 of file conversions.h.
| KDL::Rotation exotica::GetRotation | ( | Eigen::VectorXdRefConst | data, |
| RotationType | type | ||
| ) |
Definition at line 114 of file conversions.cpp.
| Eigen::VectorXd exotica::GetRotationAsVector | ( | const KDL::Frame & | val, |
| RotationType | type | ||
| ) |
Definition at line 109 of file conversions.cpp.
|
inline |
Definition at line 100 of file conversions.h.
|
inline |
Definition at line 94 of file conversions.h.
| std::string exotica::GetTypeName | ( | const std::type_info & | type | ) |
| std::vector<Val> exotica::GetValuesFromMap | ( | const std::map< Key, Val > & | map | ) |
Definition at line 207 of file conversions.h.
|
inline |
Definition at line 39 of file sparse_costs.h.
|
inline |
Definition at line 56 of file sparse_costs.h.
|
inline |
Definition at line 47 of file sparse_costs.h.
|
inline |
Definition at line 170 of file conversions.h.
|
inline |
Definition at line 37 of file collision_scene.cpp.
|
inline |
Definition at line 180 of file conversions.h.
|
inline |
Definition at line 175 of file conversions.h.
| robot_model::RobotModelPtr exotica::LoadModelImpl | ( | const std::string & | urdf, |
| const std::string & | srdf | ||
| ) |
Definition at line 62 of file server.cpp.
| void exotica::LoadOBJ | ( | const std::string & | data, |
| Eigen::VectorXi & | tri, | ||
| Eigen::VectorXd & | vert | ||
| ) |
| std::shared_ptr< octomap::OcTree > exotica::LoadOctree | ( | const std::string & | file_path | ) |
| std::shared_ptr< shapes::Shape > exotica::LoadOctreeAsShape | ( | const std::string & | file_path | ) |
| std::vector<Val> exotica::MapToVec | ( | const std::map< Key, Val > & | map | ) |
Definition at line 186 of file conversions.h.
|
inline |
Definition at line 142 of file conversions.h.
|
inline |
Definition at line 78 of file kinematic_tree.h.
| std::ostream & exotica::operator<< | ( | std::ostream & | os, |
| const Printable & | s | ||
| ) |
Definition at line 34 of file printable.cpp.
| std::ostream& exotica::operator<< | ( | std::ostream & | os, |
| const std::map< I, T > & | s | ||
| ) |
Definition at line 85 of file printable.h.
| std::ostream& exotica::operator<< | ( | std::ostream & | os, |
| const std::vector< T > & | s | ||
| ) |
Definition at line 78 of file printable.h.
|
inlinenoexcept |
Definition at line 72 of file exception.h.
|
inline |
Definition at line 73 of file kinematic_tree.h.
|
inline |
Definition at line 288 of file conversions.h.
|
inline |
Definition at line 370 of file conversions.h.
|
inline |
Definition at line 311 of file conversions.h.
|
inline |
Definition at line 324 of file conversions.h.
|
inline |
Definition at line 350 of file conversions.h.
|
inline |
Definition at line 337 of file conversions.h.
| std::string exotica::ParsePath | ( | const std::string & | path | ) |
|
inline |
Definition at line 260 of file conversions.h.
| bool exotica::parseXML | ( | tinyxml2::XMLHandle & | tag, |
| Initializer & | parent, | ||
| const std::string & | prefix | ||
| ) |
Definition at line 98 of file xml_loader.cpp.
| void exotica::PrintDimensions | ( | const std::string & | name, |
| const Eigen::Ref< const Eigen::MatrixXd > | m | ||
| ) |
Definition at line 53 of file printable.cpp.
|
inline |
Definition at line 86 of file sparse_costs.h.
|
inline |
Definition at line 96 of file sparse_costs.h.
|
inline |
Definition at line 91 of file sparse_costs.h.
| std_msgs::ColorRGBA exotica::RandomColor | ( | ) |
| void exotica::SaveMatrix | ( | std::string | file_name, |
| const Eigen::Ref< const Eigen::MatrixXd > | mat | ||
| ) |
|
inline |
Definition at line 147 of file conversions.h.
| Eigen::VectorXd exotica::SetRotation | ( | const KDL::Rotation & | data, |
| RotationType | type | ||
| ) |
Definition at line 150 of file conversions.cpp.
|
inline |
Definition at line 63 of file sparse_costs.h.
|
inline |
Definition at line 79 of file sparse_costs.h.
|
inline |
Definition at line 70 of file sparse_costs.h.
| T exotica::ToNumber | ( | const std::string & | ) |
Definition at line 236 of file conversions.h.
|
inline |
Definition at line 248 of file conversions.h.
|
inline |
Definition at line 242 of file conversions.h.
|
inline |
Definition at line 254 of file conversions.h.
| std::string exotica::ToString | ( | const Eigen::Isometry3d & | s | ) |
Definition at line 47 of file printable.cpp.
| std::string exotica::ToString | ( | const KDL::Frame & | s | ) |
Definition at line 40 of file printable.cpp.
|
inline |
Definition at line 229 of file conversions.h.
| const char exotica::branch[] |
|
constexpr |
Definition at line 70 of file kinematic_tree.h.
|
constexpr |
Definition at line 71 of file kinematic_tree.h.
| const char exotica::version[] |