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

Namespaces

 visualization
 

Classes

class  AbstractDynamicsSolver
 
class  AbstractTimeIndexedProblem
 
class  AllowedCollisionMatrix
 
struct  AttachedObject
 
class  AvoidLookAtSphere
 Avoids pointing end-effector at a given spherical object. More...
 
class  BoundedEndPoseProblem
 
class  BoundedTimeIndexedProblem
 
struct  BoxQPSolution
 
class  CenterOfMass
 
class  CollisionCheck
 
class  CollisionDistance
 
struct  CollisionProxy
 
class  CollisionScene
 
struct  ContinuousCollisionProxy
 
class  ContinuousJointPose
 
class  ControlRegularization
 
class  Distance
 
class  DistanceToLine2D
 
class  DynamicTimeIndexedShootingProblem
 
class  EffAxisAlignment
 
class  EffBox
 Limits every given end-effector motion to a box in some reference frame. More...
 
class  EffFrame
 
class  EffOrientation
 
class  EffPosition
 
class  EffPositionXY
 
class  EffVelocity
 
class  EndPoseProblem
 
struct  EndPoseTask
 
class  Exception
 
class  Factory
 
class  FeedbackMotionSolver
 
struct  FunctorBase
 
class  GazeAtConstraint
 Keeps a given point within field of view of the end-effector. More...
 
class  Initializer
 
class  InitializerBase
 
class  Instantiable
 
class  InstantiableBase
 
class  InteractionMesh
 
class  JointAccelerationBackwardDifference
 Time-derivative estimation by backward differencing. JointAccelerationBackwardDifference uses backward differencing to estimate the second time derivative of the joint state. More...
 
class  JointJerkBackwardDifference
 Time-derivative estimation by backward differencing. JointJerkBackwardDifference uses backward differencing to estimate the third time derivative of the joint state. More...
 
class  JointLimit
 Implementation of joint limits task map. Note: we dont want to always stay at the centre of the joint range, be lazy as long as the joint is not too close to the low/high limits. More...
 
class  JointPose
 
class  JointTorqueMinimizationProxy
 
class  JointVelocityBackwardDifference
 Time-derivative estimation by backward differencing. JointVelocityBackwardDifference uses backward differencing to estimate the first time derivative of the joint state. More...
 
class  JointVelocityLimit
 Joint Velocity Limit taskmap for time-indexed problems. Penalisations of joint velocity limit violation within a specified percentage of the velocity limit. More...
 
class  JointVelocityLimitConstraint
 Joint velocity limit task map for non time-indexed problems. More...
 
class  KinematicElement
 
struct  KinematicFrame
 
struct  KinematicFrameRequest
 
struct  KinematicResponse
 
class  KinematicSolution
 
struct  KinematicsRequest
 
class  KinematicTree
 
class  LookAt
 Points end-effector to look at a given target by aligning end-effector z-axis with the target. Looks at a target point by penalizing the vector which defines the orthogonal projection onto a defined line in the end-effector frame. More...
 
class  Manipulability
 Manipulability measure. The manipulability measure for a robot at a given joint configuration indicates dexterity, that is, how isotropic the robot's motion is with respect to the task space motion. The measure is high when the manipulator is capable of equal motion in all directions and low when the manipulator is close to a singularity. This task map implements Yoshikawa's manipulability measure

\[ m(x) = \sqrt{J(x)J(x)^T} \]

that is based on the shape of the velocity ellipsoid where $J(x)$ is the manipulator Jacobian matrix.. The task map is expressed by

\[ \phi(x) := -m(x). \]

. More...

 
class  MotionSolver
 
class  Object
 
class  PlanningProblem
 
class  PointToLine
 
class  PointToPlane
 
class  Printable
 
class  Property
 
class  QuasiStatic
 
class  Registrar
 
class  RosNode
 
class  SamplingProblem
 
struct  SamplingTask
 
class  Scene
 
class  Server
 
class  Setup
 
class  SmoothCollisionDistance
 
class  SolveException
 
class  SphereCollision
 
class  SumOfPenetrations
 
struct  Task
 
struct  TaskIndexing
 
class  TaskMap
 
struct  TaskSpaceVector
 
struct  TaskVectorEntry
 
class  TestCout
 
class  TimeIndexedProblem
 
class  TimeIndexedSamplingProblem
 
struct  TimeIndexedTask
 
class  Timer
 
class  Trajectory
 
class  UnconstrainedEndPoseProblem
 
class  UnconstrainedTimeIndexedProblem
 
class  Uncopyable
 
class  VariableSizeCollisionDistance
 
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
 
typedef std::shared_ptr< TaskMapTaskMapPtr
 
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
 
enum  BaseType
 
enum  ControlCostLossTermType
 
enum  Integrator
 
enum  JointLimitType
 
enum  KinematicRequestFlags
 
enum  RotationType {
  RotationType::QUATERNION, RotationType::RPY, RotationType::ZYX, RotationType::ZYZ,
  RotationType::ANGLE_AXIS, RotationType::MATRIX
}
 
enum  TerminationCriterion {
  TerminationCriterion::NotStarted, 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)
 
void AppendMap (std::map< Key, Val > &orig, const std::map< Key, Val > &extra)
 
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, 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 BoxQP (const Eigen::MatrixXd &H, const Eigen::VectorXd &q, const Eigen::VectorXd &b_low, const Eigen::VectorXd &b_high, const Eigen::VectorXd &x_init)
 
std::list< int > ConvexHull2D (Eigen::MatrixXdRefConst points)
 
double cross (Eigen::VectorXdRefConst a, Eigen::VectorXdRefConst b)
 cross 2D cross product (z coordinate of a 3D cross product of 2 vectors on a xy plane). More...
 
double DetDiff2D (Eigen::VectorXdRefConst p1, Eigen::VectorXdRefConst p2, Eigen::VectorXdRefConst p)
 DetDiff2D Computes the 2D determinant (analogous to a 2D cross product) of a two vectors defined by P_1P_2 and P_1P. More...
 
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 (double r, double g, double b, double a=1.0)
 
std_msgs::ColorRGBA GetColor (const Eigen::Vector4d &rgba)
 
KDL::Frame GetFrame (Eigen::VectorXdRefConst val)
 
Eigen::MatrixXd GetFrame (const KDL::Frame &val)
 
Eigen::VectorXd GetFrameAsVector (const KDL::Frame &val, RotationType type=RotationType::RPY)
 
KDL::Frame GetFrameFromMatrix (Eigen::MatrixXdRefConst val)
 
std::vector< std::string > GetKeys (std::map< std::string, T > map)
 
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)
 
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)
 
std::shared_ptr< octomap::OcTreeLoadOctree (const std::string &file_path)
 
std::shared_ptr< shapes::ShapeLoadOctreeAsShape (const std::string &file_path)
 
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)
 
std::ostream & operator<< (std::ostream &os, const std::vector< T > &s)
 
std::ostream & operator<< (std::ostream &os, const std::map< I, 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)
 
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 PointToLineDistance (const Eigen::Vector2d &P1, const Eigen::Vector2d &P2, const Eigen::Vector2d &P3, double &d)
 Computes the signed distance between a point and a line defined by two points in 2D. More...
 
void PointToLineDistanceDerivative (const Eigen::Vector2d &P1, const Eigen::Vector2d &P2, const Eigen::Vector2d &P3, const Eigen::MatrixXd &dP1_dq, const Eigen::MatrixXd &dP2_dq, const Eigen::MatrixXd &dP3_dq, Eigen::Ref< Eigen::MatrixXd > &derivative)
 Derivative of signed distance between a point and a line defined by two points in 2D. More...
 
void potential (double &phi, Eigen::VectorXdRefConst A, Eigen::VectorXdRefConst B, Eigen::VectorXdRefConst P)
 potential Calculates electrostatic potential at pont P induced by a uniformly charged line AB. More...
 
void potential (double &phi, Eigen::VectorXdRef jacobian, Eigen::VectorXdRefConst A, Eigen::VectorXdRefConst B, Eigen::VectorXdRefConst P, Eigen::MatrixXdRefConst A_, Eigen::MatrixXdRefConst B_, Eigen::MatrixXdRefConst P_)
 potential Calculates electrostatic potential at pont P induced by a uniformly charged line AB. More...
 
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::list< int > QuickHull (Eigen::MatrixXdRefConst points, std::list< int > &half_points, int p1, int p2)
 
std_msgs::ColorRGBA RandomColor ()
 
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)
 
ToNumber (const std::string &val)
 
double ToNumber< double > (const std::string &val)
 
float ToNumber< float > (const std::string &val)
 
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)
 
void winding (double &phi, Eigen::VectorXdRefConst A, Eigen::VectorXdRefConst B, Eigen::VectorXdRefConst P)
 winding Calculates the winding number around pont P w.r.t. thw line AB. More...
 
void winding (double &phi, Eigen::VectorXdRef jacobian, Eigen::VectorXdRefConst A, Eigen::VectorXdRefConst B, Eigen::VectorXdRefConst P, Eigen::MatrixXdRefConst A_, Eigen::MatrixXdRefConst B_, Eigen::MatrixXdRefConst P_)
 winding Calculates the winding number around pont P w.r.t. thw line AB. More...
 

Variables

 ARG0
 
 ARG1
 
 ARG2
 
 ARG3
 
 ARG4
 
const char branch []
 
constexpr double eps = 1e-8
 
 FIXED
 
 FLOATING
 
 Huber
 
constexpr double inf
 
 KIN_FK
 
 KIN_FK_VEL
 
 KIN_H
 
 KIN_J
 
 L2
 
 LIMIT_POSITION_LOWER
 
 LIMIT_POSITION_UPPER
 
constexpr double pi
 
 PLANAR
 
 PseudoHuber
 
 RK1
 
 RK2
 
 RK4
 
 SmoothL1
 
 SymplecticEuler
 
 Undefined
 
const char version []
 

Function Documentation

std::list<int> exotica::ConvexHull2D ( Eigen::MatrixXdRefConst  points)

Definition at line 78 of file convex_hull.h.

double exotica::cross ( Eigen::VectorXdRefConst  a,
Eigen::VectorXdRefConst  b 
)

cross 2D cross product (z coordinate of a 3D cross product of 2 vectors on a xy plane).

Parameters
a2D Vector.
b2D Vector.
Returns
2D cross product.

Definition at line 51 of file quasi_static.cpp.

double exotica::DetDiff2D ( Eigen::VectorXdRefConst  p1,
Eigen::VectorXdRefConst  p2,
Eigen::VectorXdRefConst  p 
)

DetDiff2D Computes the 2D determinant (analogous to a 2D cross product) of a two vectors defined by P_1P_2 and P_1P.

Definition at line 40 of file convex_hull.h.

void exotica::PointToLineDistance ( const Eigen::Vector2d &  P1,
const Eigen::Vector2d &  P2,
const Eigen::Vector2d &  P3,
double &  d 
)

Computes the signed distance between a point and a line defined by two points in 2D.

Parameters
P1First point defining the line
P2Second point defining the line
P3Query point
dSigned distance

Definition at line 49 of file distance_to_line_2d.h.

void exotica::PointToLineDistanceDerivative ( const Eigen::Vector2d &  P1,
const Eigen::Vector2d &  P2,
const Eigen::Vector2d &  P3,
const Eigen::MatrixXd &  dP1_dq,
const Eigen::MatrixXd &  dP2_dq,
const Eigen::MatrixXd &  dP3_dq,
Eigen::Ref< Eigen::MatrixXd > &  derivative 
)

Derivative of signed distance between a point and a line defined by two points in 2D.

Definition at line 57 of file distance_to_line_2d.h.

void exotica::potential ( double &  phi,
Eigen::VectorXdRefConst  A,
Eigen::VectorXdRefConst  B,
Eigen::VectorXdRefConst  P 
)

potential Calculates electrostatic potential at pont P induced by a uniformly charged line AB.

Parameters
phiPotential.
A1st point on the line.
B2nd point on the line.
PQuery point.

Definition at line 63 of file quasi_static.cpp.

potential Calculates electrostatic potential at pont P induced by a uniformly charged line AB.

Parameters
phiPotential.
jacobianGradient of the potential.
A1st point on the line.
B2nd point on the line.
PQuery point.
A_Derivative of 1st point on the line.
B_Derivative of 2nd point on the line.
P_Derivative of query point.

Definition at line 89 of file quasi_static.cpp.

std::list<int> exotica::QuickHull ( Eigen::MatrixXdRefConst  points,
std::list< int > &  half_points,
int  p1,
int  p2 
)

Definition at line 45 of file convex_hull.h.

void exotica::winding ( double &  phi,
Eigen::VectorXdRefConst  A,
Eigen::VectorXdRefConst  B,
Eigen::VectorXdRefConst  P 
)

winding Calculates the winding number around pont P w.r.t. thw line AB.

Parameters
phiWinding number.
A1st point on the line.
B2nd point on the line.
PQuery point.

Definition at line 119 of file quasi_static.cpp.

winding Calculates the winding number around pont P w.r.t. thw line AB.

Parameters
phiWinding number.
jacobianGradient of the Winding number.
A1st point on the line.
B2nd point on the line.
PQuery point.
A_Derivative of 1st point on the line.
B_Derivative of 2nd point on the line.
P_Derivative of query point.

Definition at line 137 of file quasi_static.cpp.

Variable Documentation

constexpr double exotica::eps = 1e-8

Definition at line 40 of file quasi_static.cpp.



exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09