ocra-recipes
Doxygen documentation for the ocra-recipes repository
Namespaces | Classes | Typedefs | Enumerations | Functions
ocra Namespace Reference

Optimization-based Robot Controller namespace. a library of classes to write and solve optimization problems dedicated to the control of multi-body systems. More...

Namespaces

 fsqpDetails
 
 util
 
 utils
 

Classes

class  AbilitySet
 
class  BaseVariable
 Implements a basic variable. More...
 
class  BoundFunction
 BoundFunction class. More...
 
class  Buffer
 
class  CartesianTaskBuilder
 
class  CascadeQP
 CascadeQP class. More...
 
class  CascadeQPSolver
 CascadeQPSolver class. More...
 
class  CmlQuadraticSolver
 CmlQuadraticSolver class. More...
 
class  CoMFrame
 Creates a frame whose center is at the CoM of the model and whose axes are parallel to the axes of the world frame. More...
 
class  Component
 Base class for the Component class of the Composite pattern. More...
 
class  Composite
 Base class for the Composite class of the Composite pattern. More...
 
class  CompositeVariable
 A concatenation of base variables and other composite variables. More...
 
class  ComTaskBuilder
 
class  Constraint
 Constraint class. More...
 
class  Constraint< Function >
 
class  ConstraintSet
 ConstraintSet class. More...
 
class  ConstraintSet< Function >
 
class  ContactAvoidanceConstraint
 
class  ContactAvoidanceFunction
 Create a linear function that represents the joint limit function. More...
 
class  ContactConstraintFeature
 Used to build contact constraint tasks (null acceleration). More...
 
class  ContactSet
 Contact task factory. More...
 
class  ControlConstraint
 
class  ControlFrame
 Generic representation of a frame: gives access to its position, velocity, jacobian... More...
 
class  Controller
 Interface for controllers. More...
 
class  CoupledInputOutputSize
 
class  DiagonalLinearFunction
 DiagonalLinearFunction class. More...
 
class  DisplacementFeature
 Used to build position/orientation tasks. More...
 
class  DotProductFunction
 DotProductFunction class. More...
 
class  DoubleDiagonalLinearFunction
 DoubleDiagonalLinearFunction class. More...
 
class  DynamicEquationFunction
 DynamicEquationFunction class. More...
 
struct  EqualitiesConstraints
 
class  EqualZeroConstraintPtr
 
class  Ex1Pb
 
class  Ex2Pb
 
class  Ex3Pb
 
class  Ex4Pb
 
class  Ex5Pb
 
class  ExperimentalTrajectory
 
class  FcQuadraticFunction
 
class  Feature
 Feature interface, used by tasks to compute errors and jacobians. More...
 
struct  FinalSolution
 
class  FSQPConstraintManager
 FSQPConstraintManager class. More...
 
class  FSQPSolver
 FSQPSolver class. More...
 
class  FullContactAvoidanceFunction
 Create a linear function that represents the contact avoidance function for the full formalism. More...
 
class  FullDynamicEquationFunction
 Create a linear function that represents the dynamic equation of motion. More...
 
class  FullJointLimitFunction
 Create a linear function that represents the joint limit function for the full formalism. More...
 
class  FullModelState
 
class  FullPostureTaskBuilder
 
class  FullState
 
class  FullStateFeature
 Used to build tasks in the manikin configuration space. More...
 
class  FullTargetState
 
class  Function
 Function class. More...
 
struct  FunctionInterfaceMapping
 
struct  FunctionInterfaceMapping< X< Function > >
 
class  GaussianProcessTrajectory
 
class  GreaterThanZeroConstraintPtr
 
struct  HierarchyLevel
 
struct  HierarchyLevel_barre
 
class  IdentityFunction
 IdentityFunction class. More...
 
class  IFunction
 Computation ability of a ocra function. More...
 
class  IFunctionProperties
 
struct  InequalitiesConstraints
 
class  Invoker
 
class  Invoker< T, EVT, false >
 
class  Invoker< T, EVT, true >
 
class  Invoker< void, EVT, false >
 
class  Invoker< void, EVT, true >
 
class  InvokerBase
 
class  JointLimitConstraint
 
class  JointLimitFunction
 Create a linear function that represents the joint limit function. More...
 
class  Leaf
 Base class for the Leaf class of the Composite pattern. More...
 
class  LessThanZeroConstraintPtr
 
class  LinearFunction
 LinearFunction class. More...
 
class  LinearInterpolationTrajectory
 
class  LinearizedCoulombFunction
 LinearizedCoulombFunction class. More...
 
class  LinearTask
 LinearTask class. More...
 
struct  MatrixPQ
 
class  MergedVariable
 
class  MinimumJerkTrajectory
 
class  Model
 Model class. More...
 
class  ModelContacts
 ModelContacts class. More...
 
class  NamedInstance
 
class  NewtonSolver
 NewtonSolver class. More...
 
struct  NoInfo
 Empty information block to attach to a parenthood relationship between a Composite and a Component. More...
 
class  Objective
 Objective class. More...
 
class  Objective< Function >
 
class  ObjectivePtr
 
class  ObjQLD
 ObjQLD class. More...
 
class  Observer
 
class  ObserverBase
 Base class for Observers with propagation system. More...
 
class  ObserverSubject
 
struct  ocra_static_assert
 
struct  ocra_static_assert< true >
 
class  OFSQP
 
class  OFSQPProblem
 
class  OneLevelSolver
 A generic abstract class the solvers that can be used in the wOcra Controller. More...
 
class  OneLevelSolverWithQLD
 Solver class that only consider one level of importance for all tasks using QLD. More...
 
class  OneLevelSolverWithQPOASES
 Solver class that only consider one level of importance for all tasks using QPOASES. More...
 
class  OneLevelSolverWithQuadProg
 Solver class that only consider one level of importance for all tasks using Quadprog++. More...
 
struct  OptimizationResult
 
class  OrientationFeature
 Used to build orientation tasks. More...
 
class  OrientationTaskBuilder
 
class  Parenthood
 Stores information about a Parent/Child relationship in the Composite design pattern. More...
 
class  PartialModelState
 A partial state of the model. More...
 
class  PartialPostureTaskBuilder
 
class  PartialState
 A abstract partial state. More...
 
class  PartialStateFeature
 Used to build tasks in a partial configuration space. More...
 
class  PartialTargetState
 A target for a model partial state. More...
 
class  Pb114G10
 
class  Pb114G11
 
class  Pb114G5
 
class  PointContactFeature
 Used to build point contact tasks. More...
 
class  PointContactTaskBuilder
 
class  PoseTaskBuilder
 
class  PositionFeature
 Used to build positioning tasks. More...
 
class  QLDSolver
 QLDSolver class. More...
 
class  QuadraticFunction
 QuadraticFunction class. More...
 
class  QuadraticSolver
 QuadraticSolver class. More...
 
class  ReducedContactAvoidanceFunction
 Create a linear function that represents the contact avoidance function for the reduced formalism. More...
 
class  ReducedJointLimitFunction
 Create a linear function that represents the joint limit function for the reduced formalism. More...
 
struct  return_type_traits
 type and function definitions for the return types. More...
 
class  RowFunction
 RowFunction class. More...
 
class  SecondOrderLinearTask
 SecondOrderLinearTask class. More...
 
class  SegmentFrame
 A frame attached to a segment of a model. More...
 
struct  Solution
 
class  Solver
 Solver class. More...
 
class  SquaredLinearFunction
 SquaredLinearFunction class. More...
 
class  Subject
 
class  SubjectBase
 
struct  SubjectBaseTraits
 
struct  SubjectBaseTraits< EVT, void >
 
struct  SubjectBaseTraitsBase
 Base class for objects who can raise events,. More...
 
class  SubtractionFunction
 SubtractionFunction class. More...
 
class  SumOfLinearFunctions
 
class  TargetFrame
 Represents a 'target', i.e. something that does not depend on a model but must match with another frame. More...
 
class  Task
 
class  TaskBuilder
 
class  TaskBuilderOptions
 
class  TaskConstructionManager
 
class  TaskMessageHandler
 
class  TaskState
 
class  TaskYarpInterface
 
class  TimeOptimalTrajectory
 
class  TorqueLimitConstraint
 
class  TorqueLimitFunction
 Create a linear function that represents the torque limit function. More...
 
class  Trajectory
 
class  Variable
 This class represents a variable in a mathematical sense. More...
 
class  VariableChiFunction
 
class  VariableHasRestrictedClassDerivation
 
class  VariableMapping
 A class to manage the relative mapping of a variable with respect to another one. More...
 
struct  VariableParenthood
 This class stores information about a composite-component relationship. More...
 
class  WeightedSquareDistanceFunction
 WeightedSquareDistanceFunction class. More...
 

Typedefs

typedef std::vector< bool > boolVector
 
typedef Constraint< FunctionGenericConstraint
 
typedef Constraint< LinearFunctionLinearConstraint
 
typedef Constraint< BoundFunctionBoundConstraint
 
typedef Constraint< IdentityFunctionIdentityConstraint
 
typedef Constraint< DiagonalLinearFunctionDiagonalLinearConstraint
 
typedef Objective< FunctionGenericObjective
 
typedef Objective< LinearFunctionLinearObjective
 
typedef Objective< QuadraticFunctionQuadraticObjective
 
typedef Objective< SquaredLinearFunctionSquaredLinearObjective
 
typedef Eigen::Map< Eigen::MatrixXd > MatrixMap
 
typedef Eigen::Map< Eigen::VectorXd > VectorMap
 
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > MatrixXdRm
 
typedef double real
 
typedef Eigen::DenseBase< MatrixXd >::ConstRowXpr MatrixXdRow
 
typedef Eigen::Matrix< double, 6, 1 > Vector6d
 
typedef Eigen::Matrix< double, 6, 6 > Matrix6d
 
typedef Eigen::Matrix< double, 3, Eigen::Dynamic > Jacobian3d
 
typedef Eigen::Matrix< double, 6, Eigen::Dynamic > Jacobian6d
 

Enumerations

enum  ECartesianDof {
  NONE =0, X, Y, XY,
  Z, XZ, YZ, XYZ
}
 
enum  TASK_MODE { TASK_AS_OBJECTIVE, TASK_AS_CONSTRAINT, TASK_NOT_DEFINED }
 A basic enumeration for the different types of tasks we can have. More...
 
enum  TASK_MESSAGE {
  OCRA_FAILURE = 0, OCRA_SUCCESS, OCRA_WARNING, GET_CURRENT_STATE,
  GET_STIFFNESS, GET_DAMPING, GET_WEIGHTS, GET_ACTIVITY_STATUS,
  GET_DIMENSION, GET_TYPE, GET_TYPE_AS_STRING, GET_NAME,
  GET_CONTROL_PORT_NAMES, GET_TASK_PORT_NAME, GET_TASK_ERROR, GET_TASK_STATE,
  GET_DESIRED_TASK_STATE, GET_TASK_POSITION, GET_DESIRED_TASK_POSITION, SET_STIFFNESS,
  SET_STIFFNESS_VECTOR, SET_STIFFNESS_MATRIX, SET_DAMPING, SET_DAMPING_VECTOR,
  SET_DAMPING_MATRIX, SET_WEIGHT, SET_WEIGHT_VECTOR, SET_DESIRED_TASK_STATE,
  SET_DESIRED_TASK_POSITION, ACTIVATE, DEACTIVATE, TASK_IS_ACTIVATED,
  TASK_IS_DEACTIVATED, OPEN_CONTROL_PORTS, CLOSE_CONTROL_PORTS, HELP
}
 
enum  eBoundType { BOUND_TYPE_INFERIOR = -1, BOUND_TYPE_SUPERIOR = 1 }
 
enum  eConstraintType {
  CSTR_EQUAL_ZERO =0, CSTR_EQUAL_B, CSTR_LOWER_ZERO, CSTR_LOWER_U,
  CSTR_GREATER_ZERO, CSTR_GREATER_L, CSTR_LOWER_AND_GREATER
}
 
enum  eFunctionAbility {
  FUN_VALUE = 0, PARTIAL_X, PARTIAL_T, FUN_DOT,
  PARTIAL_X_DOT, PARTIAL_XX, FUN_DDOT, PARTIAL_TT,
  PARTIAL_TX, PARTIAL_XT, PARTIAL_T_DOT, PARTIAL_X_DOT_X_DOT,
  PROP_NUMBER
}
 Enumeration of the computation abilities of a ocra function. More...
 
enum  eFunctionContinuity {
  CONTINUITY_C0 = 0, CONTINUITY_C1, CONTINUITY_C2, CONTINUITY_C3,
  CONTINUITY_C4, CONTINUITY_CINF = 0xfff-1, CONTINUITY_UNKNOWN
}
 
enum  eFunctionLinearity {
  LINEARITY_CONSTANT, LINEARITY_LINEAR, LINEARITY_QUADRATIC, LINEARITY_LINEAR_FRACTIONAL,
  LINEARITY_UNDEFINED
}
 
enum  eFunctionConvexity {
  CONVEXITY_CONVEX, CONVEXITY_STRICTLY_CONVEX, CONVEXITY_CONCAVE, CONVEXITY_STRICTLY_CONCAVE,
  CONVEXITY_CONVEX_AND_CONCAVE, CONVEXITY_LOG_CONVEX, CONVEXITY_LOG_CONCAVE, CONVEXITY_QUASICONVEX,
  CONVEXITY_QUASICONCAVE, CONVEXITY_QUASILINEAR, CONVEXITY_UNDEFINED
}
 
enum  {
  EVT_RESIZE = 0xffff, EVT_CHANGE_DEPENDENCIES, EVT_CHANGE_VALUE, EVT_INVALIDATE,
  EVT_CSTR_CHANGE_BOUNDS_NUMBER
}
 
enum  eReturnInfo {
  RETURN_SUCCESS = 0, RETURN_INCONSISTENT_PROBLEM, RETURN_INFEASIBLE_PROBLEM, RETURN_MAX_ITER_REACHED,
  RETURN_MAX_TIME_REACHED, RETURN_MEMORY_ERROR, RETURN_NUMERICAL_ERROR, RETURN_ERROR
}
 
enum  eConstraintOutput {
  CSTR_PLUS_EQUAL =0, CSTR_MINUS_EQUAL, CSTR_PLUS_LOWER, CSTR_MINUS_LOWER,
  CSTR_PLUS_GREATER, CSTR_MINUS_GREATER, CSTR_DOUBLE_BOUNDS
}
 

Functions

AbilitySet operator& (const AbilitySet a1, const AbilitySet a2)
 
AbilitySet operator| (const AbilitySet a1, const AbilitySet a2)
 
std::ostream & operator<< (std::ostream &out, const HierarchyLevel &h)
 
std::ostream & operator<< (std::ostream &out, const HierarchyLevel_barre &h)
 
std::ostream & operator<< (std::ostream &out, const MatrixPQ &m)
 
std::ostream & operator<< (std::ostream &out, const EqualitiesConstraints &e)
 
std::ostream & operator<< (std::ostream &out, const InequalitiesConstraints &ie)
 
std::ostream & operator<< (std::ostream &out, const FinalSolution &sf)
 
void testSolveCmlQP (void)
 
void testSolveCmlQPWithNonFeasiblePb (void)
 
void testDiagonalLinearFunction ()
 
void testFsqpMapping ()
 
void testFSQPSolver01 ()
 
void testFSQPSolver02 ()
 
 DECLARE_SUBTYPE_TRAITS (VectorXd, double,, operator[])
 
 DECLARE_SUBTYPE_TRAITS (MatrixXd, MatrixXdRow,, row)
 
 DECLARE_SUBTYPE_TRAITS (std::vector< MatrixXd * >, const MatrixXd &,*, operator[])
 
 DECLARE_FUNCTION_TRAITS (eFunctionAbility Property,, int, updateProperty,-1)
 
 DECLARE_FUNCTION_TRAITS (,< FUN_VALUE >, VectorXd, updateValue, FUN_VALUE)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_X >, MatrixXd, updateJacobian, PARTIAL_X)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_T >, VectorXd, updatePartialT, PARTIAL_T)
 
 DECLARE_FUNCTION_TRAITS (,< FUN_DOT >, VectorXd, updateFdot, FUN_DOT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_X_DOT >, MatrixXd, updateJdot, PARTIAL_X_DOT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_XX >, std::vector< MatrixXd * >, updateHessian, PARTIAL_XX)
 
 DECLARE_FUNCTION_TRAITS (,< FUN_DDOT >, VectorXd, updateFddot, FUN_DDOT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_TT >, VectorXd, updatePartialTT, PARTIAL_TT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_TX >, MatrixXd, updatePartialTX, PARTIAL_TX)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_XT >, MatrixXd, updatePartialXT, PARTIAL_XT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_T_DOT >, VectorXd, updatePartialTdot, PARTIAL_T_DOT)
 
 DECLARE_FUNCTION_TRAITS (,< PARTIAL_X_DOT_X_DOT >, VectorXd, updateJdotXdot, PARTIAL_X_DOT_X_DOT)
 
void testLinearFunction ()
 
void testLinearCoulomb (void)
 
void testLinearTask ()
 
void testNewtonSolver01 ()
 
void testNewtonSolver02 ()
 
void testObjQLD (void)
 
void testOFSQP01 ()
 
void testOFSQP02a ()
 
void testOFSQP02b ()
 
void testOFSQP03 ()
 
void testOFSQP04 ()
 
void testOFSQP05 ()
 
void testQLDSolver ()
 
void testQuadraticFunction ()
 
void testUtilities ()
 
void testSquaredLinearFunction ()
 
void testWeightedSquareDistanceFunction ()
 
double deg2rad (const double deg)
 
double rad2deg (const double rad)
 
bool operator< (const FSQPConstraintManager::Mapping &m1, const FSQPConstraintManager::Mapping &m2)
 

Detailed Description

Optimization-based Robot Controller namespace. a library of classes to write and solve optimization problems dedicated to the control of multi-body systems.

QuadraticFunction dedicated to the minimization of the force of contact (fc) variable.

Typedef Documentation

typedef std::vector<bool> ocra::boolVector

Definition at line 15 of file GaussianProcessTrajectory.h.

Definition at line 674 of file Constraint.h.

Definition at line 676 of file Constraint.h.

Definition at line 672 of file Constraint.h.

Definition at line 147 of file Objective.h.

Definition at line 675 of file Constraint.h.

typedef Eigen::Matrix<double,3,Eigen::Dynamic> ocra::Jacobian3d

Definition at line 38 of file MathTypes.h.

typedef Eigen::Matrix<double,6,Eigen::Dynamic> ocra::Jacobian6d

Definition at line 39 of file MathTypes.h.

Definition at line 673 of file Constraint.h.

Definition at line 148 of file Objective.h.

typedef Eigen::Matrix<double,6,6> ocra::Matrix6d

Definition at line 37 of file MathTypes.h.

typedef Eigen::DenseBase<MatrixXd>::ConstRowXpr ocra::MatrixXdRow

Definition at line 29 of file MathTypes.h.

Definition at line 149 of file Objective.h.

typedef double ocra::real

Definition at line 27 of file MathTypes.h.

Definition at line 150 of file Objective.h.

typedef Eigen::Matrix<double,6,1> ocra::Vector6d

Definition at line 36 of file MathTypes.h.

Enumeration Type Documentation

anonymous enum

a list of event used in ocra

Enumerator
EVT_RESIZE 
EVT_CHANGE_DEPENDENCIES 
EVT_CHANGE_VALUE 
EVT_INVALIDATE 
EVT_CSTR_CHANGE_BOUNDS_NUMBER 

Definition at line 11 of file ocra_events.h.

Enumeration of the type of bounds. Value in the enum are important, they are used to perform computations.

Enumerator
BOUND_TYPE_INFERIOR 
BOUND_TYPE_SUPERIOR 

Definition at line 31 of file BoundFunction.h.

Enumerator
NONE 
XY 
XZ 
YZ 
XYZ 

Definition at line 18 of file ControlEnum.h.

Enumerates the possible forms of a linear constraint

Enumerator
CSTR_PLUS_EQUAL 
CSTR_MINUS_EQUAL 
CSTR_PLUS_LOWER 
CSTR_MINUS_LOWER 
CSTR_PLUS_GREATER 
CSTR_MINUS_GREATER 
CSTR_DOUBLE_BOUNDS 

Definition at line 42 of file SolverUtilities.h.

Enumerate the different types of equality/inequality constraints

Enumerator
CSTR_EQUAL_ZERO 
CSTR_EQUAL_B 
CSTR_LOWER_ZERO 
CSTR_LOWER_U 
CSTR_GREATER_ZERO 
CSTR_GREATER_L 
CSTR_LOWER_AND_GREATER 

Definition at line 49 of file Constraint.h.

Enumeration of the computation abilities of a ocra function.

[ADD-IN] if you wish to add an ability insert an element in this enumeration before PROP_NUMBER

See also
IFunction
Enumerator
FUN_VALUE 
PARTIAL_X 
PARTIAL_T 
FUN_DOT 
PARTIAL_X_DOT 
PARTIAL_XX 
FUN_DDOT 
PARTIAL_TT 
PARTIAL_TX 
PARTIAL_XT 
PARTIAL_T_DOT 
PARTIAL_X_DOT_X_DOT 
PROP_NUMBER 

Definition at line 64 of file IFunction.h.

Enumerates the different continuity level of a function

Enumerator
CONTINUITY_C0 
CONTINUITY_C1 
CONTINUITY_C2 
CONTINUITY_C3 
CONTINUITY_C4 
CONTINUITY_CINF 
CONTINUITY_UNKNOWN 

Definition at line 30 of file IFunctionProperties.h.

Enumerates the possible convexity properties of a function

Enumerator
CONVEXITY_CONVEX 
CONVEXITY_STRICTLY_CONVEX 
CONVEXITY_CONCAVE 
CONVEXITY_STRICTLY_CONCAVE 
CONVEXITY_CONVEX_AND_CONCAVE 
CONVEXITY_LOG_CONVEX 
CONVEXITY_LOG_CONCAVE 
CONVEXITY_QUASICONVEX 
CONVEXITY_QUASICONCAVE 
CONVEXITY_QUASILINEAR 
CONVEXITY_UNDEFINED 

Definition at line 52 of file IFunctionProperties.h.

Enumerates the possible linearity properties of a function

Enumerator
LINEARITY_CONSTANT 
LINEARITY_LINEAR 
LINEARITY_QUADRATIC 
LINEARITY_LINEAR_FRACTIONAL 
LINEARITY_UNDEFINED 

Definition at line 42 of file IFunctionProperties.h.

Enumerator
RETURN_SUCCESS 
RETURN_INCONSISTENT_PROBLEM 
RETURN_INFEASIBLE_PROBLEM 
RETURN_MAX_ITER_REACHED 
RETURN_MAX_TIME_REACHED 
RETURN_MEMORY_ERROR 
RETURN_NUMERICAL_ERROR 
RETURN_ERROR 

Definition at line 21 of file SolverUtilities.h.

Enumerator
OCRA_FAILURE 
OCRA_SUCCESS 
OCRA_WARNING 
GET_CURRENT_STATE 
GET_STIFFNESS 
GET_DAMPING 
GET_WEIGHTS 
GET_ACTIVITY_STATUS 
GET_DIMENSION 
GET_TYPE 
GET_TYPE_AS_STRING 
GET_NAME 
GET_CONTROL_PORT_NAMES 
GET_TASK_PORT_NAME 
GET_TASK_ERROR 
GET_TASK_STATE 
GET_DESIRED_TASK_STATE 
GET_TASK_POSITION 
GET_DESIRED_TASK_POSITION 
SET_STIFFNESS 
SET_STIFFNESS_VECTOR 
SET_STIFFNESS_MATRIX 
SET_DAMPING 
SET_DAMPING_VECTOR 
SET_DAMPING_MATRIX 
SET_WEIGHT 
SET_WEIGHT_VECTOR 
SET_DESIRED_TASK_STATE 
SET_DESIRED_TASK_POSITION 
ACTIVATE 
DEACTIVATE 
TASK_IS_ACTIVATED 
TASK_IS_DEACTIVATED 
OPEN_CONTROL_PORTS 
CLOSE_CONTROL_PORTS 
HELP 

Definition at line 18 of file TaskYarpInterfaceVocab.h.

A basic enumeration for the different types of tasks we can have.

Enumerator
TASK_AS_OBJECTIVE 
TASK_AS_CONSTRAINT 
TASK_NOT_DEFINED 

Definition at line 29 of file TaskYarpInterface.h.

Function Documentation

ocra::DECLARE_FUNCTION_TRAITS ( eFunctionAbility  Property,
int  ,
updateProperty  ,
1 
)
ocra::DECLARE_FUNCTION_TRAITS ( < FUN_VALUE ,
VectorXd  ,
updateValue  ,
FUN_VALUE   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_X ,
MatrixXd  ,
updateJacobian  ,
PARTIAL_X   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_T ,
VectorXd  ,
updatePartialT  ,
PARTIAL_T   
)
ocra::DECLARE_FUNCTION_TRAITS ( < FUN_DOT ,
VectorXd  ,
updateFdot  ,
FUN_DOT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_X_DOT ,
MatrixXd  ,
updateJdot  ,
PARTIAL_X_DOT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_XX ,
std::vector< MatrixXd * >  ,
updateHessian  ,
PARTIAL_XX   
)
ocra::DECLARE_FUNCTION_TRAITS ( < FUN_DDOT ,
VectorXd  ,
updateFddot  ,
FUN_DDOT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_TT ,
VectorXd  ,
updatePartialTT  ,
PARTIAL_TT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_TX ,
MatrixXd  ,
updatePartialTX  ,
PARTIAL_TX   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_XT ,
MatrixXd  ,
updatePartialXT  ,
PARTIAL_XT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_T_DOT ,
VectorXd  ,
updatePartialTdot  ,
PARTIAL_T_DOT   
)
ocra::DECLARE_FUNCTION_TRAITS ( < PARTIAL_X_DOT_X_DOT ,
VectorXd  ,
updateJdotXdot  ,
PARTIAL_X_DOT_X_DOT   
)
ocra::DECLARE_SUBTYPE_TRAITS ( VectorXd  ,
double  ,
operator  [] 
)
ocra::DECLARE_SUBTYPE_TRAITS ( MatrixXd  ,
MatrixXdRow  ,
row   
)
ocra::DECLARE_SUBTYPE_TRAITS ( std::vector< MatrixXd * >  ,
const MatrixXd &  ,
,
operator  [] 
)
double ocra::deg2rad ( const double  deg)
inline

Definition at line 46 of file MathTypes.h.

AbilitySet ocra::operator& ( const AbilitySet  a1,
const AbilitySet  a2 
)
inline

Element by element and and of two AbilitySet

Definition at line 119 of file AbilitySet.h.

bool ocra::operator< ( const FSQPConstraintManager::Mapping m1,
const FSQPConstraintManager::Mapping m2 
)

Definition at line 17 of file FSQPConstraintManager.cpp.

std::ostream& ocra::operator<< ( std::ostream &  out,
const HierarchyLevel h 
)
std::ostream& ocra::operator<< ( std::ostream &  out,
const HierarchyLevel_barre h 
)
std::ostream& ocra::operator<< ( std::ostream &  out,
const MatrixPQ m 
)
std::ostream& ocra::operator<< ( std::ostream &  out,
const EqualitiesConstraints e 
)
std::ostream& ocra::operator<< ( std::ostream &  out,
const InequalitiesConstraints ie 
)
std::ostream& ocra::operator<< ( std::ostream &  out,
const FinalSolution sf 
)
AbilitySet ocra::operator| ( const AbilitySet  a1,
const AbilitySet  a2 
)
inline

Definition at line 130 of file AbilitySet.h.

double ocra::rad2deg ( const double  rad)
inline

Definition at line 47 of file MathTypes.h.

void ocra::testDiagonalLinearFunction ( )

Definition at line 162 of file DiagonalLinearFunction.cpp.

void ocra::testFsqpMapping ( )

Definition at line 235 of file FSQPConstraintManager.cpp.

void ocra::testFSQPSolver01 ( )

Definition at line 493 of file FSQPSolver.cpp.

void ocra::testFSQPSolver02 ( )

Definition at line 652 of file FSQPSolver.cpp.

void ocra::testLinearCoulomb ( void  )

Definition at line 117 of file LinearizedCoulombFunction.cpp.

void ocra::testLinearFunction ( )

Definition at line 114 of file LinearFunction.cpp.

void ocra::testLinearTask ( )

Definition at line 163 of file LinearTask.cpp.

void ocra::testNewtonSolver01 ( )

Definition at line 253 of file NewtonSolver.cpp.

void ocra::testNewtonSolver02 ( )

Definition at line 293 of file NewtonSolver.cpp.

void ocra::testObjQLD ( void  )
void ocra::testOFSQP01 ( )

Definition at line 3722 of file OFSQP.cpp.

void ocra::testOFSQP02a ( )

Definition at line 3807 of file OFSQP.cpp.

void ocra::testOFSQP02b ( )

Definition at line 3859 of file OFSQP.cpp.

void ocra::testOFSQP03 ( )

Definition at line 3966 of file OFSQP.cpp.

void ocra::testOFSQP04 ( )

Definition at line 4077 of file OFSQP.cpp.

void ocra::testOFSQP05 ( )

Definition at line 4167 of file OFSQP.cpp.

void ocra::testQLDSolver ( )

Definition at line 377 of file QLDSolver.cpp.

void ocra::testQuadraticFunction ( )

Definition at line 169 of file QuadraticFunction.cpp.

void ocra::testSolveCmlQP ( void  )
void ocra::testSolveCmlQPWithNonFeasiblePb ( void  )
void ocra::testSquaredLinearFunction ( )

Definition at line 107 of file SquaredLinearFunction.cpp.

void ocra::testUtilities ( )

Definition at line 77 of file SolverUtilities.cpp.

void ocra::testWeightedSquareDistanceFunction ( void  )

Definition at line 120 of file WeightedSquareDistanceFunction.cpp.