sot-core
4.11.8
Hierarchical task solver plug-in for dynamic-graph.
|
Namespaces | |
command | |
core | |
detail | |
internal | |
Classes | |
class | NamedVector |
class | AbstractSotExternalInterface |
class | AdditionalFunctions |
This helper class dynamically overloads the "new" shell command to allow creation of tasks and features as well as entities. More... | |
class | BinaryIntToUint |
class | BinaryOp |
class | CausalFilter |
class | ClampWorkspace |
class | CoMFreezer |
class | Contiifstream |
class | ControlGR |
class | ControlPD |
class | DebugTrace |
class | Derivator |
class | Device |
class | DoubleConstant |
class | Event |
class | ExceptionAbstract |
class | ExceptionDynamic |
class | ExceptionFactory |
class | ExceptionFeature |
class | ExceptionSignal |
class | ExceptionTask |
class | ExceptionTools |
class | ExpMovingAvg |
class | Feature1D |
Simple test: the task is defined to be e_2 = .5 . e'.e, with e the mother task. The jacobian is then J_2 = e'.J, J being the jacobian of the mother task. More... | |
class | FeatureAbstract |
This class gives the abstract definition of a feature. More... | |
class | FeatureReferenceHelper |
class | FeatureGeneric |
Class that defines a generic implementation of the abstract interface for features. More... | |
class | FeatureJointLimits |
Class that defines gradient vector for jl avoidance. More... | |
class | FeatureLineDistance |
Class that defines point-3d control feature. More... | |
class | FeaturePoint6dRelative |
Class that defines the motion of a point of the body wrt. another point. More... | |
class | FeaturePoint6d |
Class that defines point-6d control feature. More... | |
class | FeaturePose |
Feature that controls the relative (or absolute) pose between two frames A (or world) and B. More... | |
class | FeaturePosture |
class | FeatureTask |
class | FeatureVector3 |
Class that defines point-3d control feature. More... | |
class | FeatureVisualPoint |
Class that defines 2D visualPoint visual feature. More... | |
class | FilterDifferentiator |
class | FIRFilter |
class | Flags |
class | GainAdaptive |
class | GainHyperbolic |
Hyperbolic gain. It follows the law. More... | |
class | GradientAscent |
class | GripperControl |
The goal of this entity is to ensure that the maximal torque will not be exceeded during a grasping task. If the maximal torque is reached, then the current position of the gripper is kept. More... | |
class | GripperControlPlugin |
class | IntegratorAbstract |
integrates an ODE. If Y is the output and X the input, the following equation is integrated: a_p * d(p)Y / dt^p + .... + a_0 Y = b_m * d(m)X / dt^m + ... . b_0 X a_i are the coefficients of the denominator of the associated transfer function between X and Y, while the b_i are those of the numerator. More... | |
class | IntegratorEuler |
integrates an ODE using a naive Euler integration. TODO: change the integration method. For the moment, the highest derivative of the output signal is computed using the previous values of the other derivatives and the input signal, then integrated n times, which will most certainly induce a huge drift for ODEs with a high order at the denominator. More... | |
class | JointLimitator |
Filter control vector to avoid exceeding joint maximum values. More... | |
class | SotJointTrajectoryEntity |
This object handles trajectory of quantities and publish them as signals. More... | |
class | Kalman |
class | Latch |
class | MadgwickAHRS |
struct | MailboxTimestampedObject |
class | Mailbox |
class | MatrixConstant |
class | MemoryTaskSOT |
class | MotionPeriod |
class | MultiBound |
class | NeckLimitation |
class | OpPointModifier |
Compute position and jacobian of a local frame attached to a joint. More... | |
class | ParameterServer |
class | PeriodicCallEntity |
class | PeriodicCall |
class | PoolStorage |
This singleton class keep tracks of all features and tasks. More... | |
class | RobotSimu |
struct | JointLimits |
class | ExtractJointMimics |
struct | ForceLimits |
struct | ForceUtil |
struct | FootUtil |
struct | HandUtil |
struct | RobotUtil |
class | Sequencer |
class | SmoothReach |
class | SotLoader |
This class is loading the control part of the Stack-Of-Tasks. More... | |
class | Sot |
This class implements the Stack of Task. It allows to deal with the priority of the controllers through the shell. More... | |
class | Switch |
Switch. More... | |
class | TaskAbstract |
class | TaskConti |
class | TaskPD |
class | TaskUnilateral |
class | Task |
Class that defines the basic elements of a task. More... | |
class | TimeStamp |
class | RulesJointTrajectory |
class | timestamp |
class | Header |
class | JointTrajectoryPoint |
class | Trajectory |
class | UnaryOp |
class | VariadicAbstract |
class | VariadicOp |
class | VectorConstant |
class | VectorToRotation |
class | VisualPointProjecter |
Typedefs | |
typedef NamedVector | SensorValues |
typedef NamedVector | ControlValues |
typedef FeaturePose< R3xSO3Representation > | FeaturePose_t |
typedef FeaturePose< SE3Representation > | FeaturePoseSE3_t |
typedef pinocchio::CartesianProductOperation< pinocchio::VectorSpaceOperationTpl< 3, double >, pinocchio::SpecialOrthogonalOperationTpl< 3, double > > | R3xSO3_t |
typedef pinocchio::SpecialEuclideanOperationTpl< 3, double > | SE3_t |
typedef Mailbox< dynamicgraph::Vector > | MailboxVector |
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > | MatrixRXd |
typedef Eigen::Map< MatrixRXd > | SigMatrixXd |
typedef Eigen::Map< Eigen::VectorXd > | SigVectorXd |
typedef const Eigen::Map< const MatrixRXd > | const_SigMatrixXd |
typedef const Eigen::Map< const Eigen::VectorXd > | const_SigVectorXd |
typedef Eigen::Ref< Eigen::VectorXd > | RefVector |
typedef const Eigen::Ref< const Eigen::VectorXd > & | ConstRefVector |
typedef Eigen::Ref< Eigen::MatrixXd > | RefMatrix |
typedef const Eigen::Ref< const Eigen::MatrixXd > | ConstRefMatrix |
typedef Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT | MatrixHomogeneous |
typedef Eigen::Matrix< double, 3, 3 > SOT_CORE_EXPORT | MatrixRotation |
typedef Eigen::AngleAxis< double > SOT_CORE_EXPORT | VectorUTheta |
typedef Eigen::Quaternion< double > SOT_CORE_EXPORT | VectorQuaternion |
typedef Eigen::Vector3d SOT_CORE_EXPORT | VectorRotation |
typedef Eigen::Vector3d SOT_CORE_EXPORT | VectorRollPitchYaw |
typedef Eigen::Matrix< double, 6, 6 > SOT_CORE_EXPORT | MatrixForce |
typedef Eigen::Matrix< double, 6, 6 > SOT_CORE_EXPORT | MatrixTwist |
typedef Eigen::Matrix< double, 7, 1 > SOT_CORE_EXPORT | Vector7 |
typedef Eigen::Quaternion< double > SOT_CORE_EXPORT | Quaternion |
typedef Eigen::Map< Quaternion > SOT_CORE_EXPORT | QuaternionMap |
typedef std::vector< MultiBound > | VectorMultiBound |
typedef Eigen::VectorXd::Index | Index |
typedef std::shared_ptr< RobotUtil > | RobotUtilShrPtr |
Accessors - This should be changed to RobotUtilPtrShared. More... | |
Enumerations | |
enum | ControlInput { CONTROL_INPUT_NO_INTEGRATION = 0 , CONTROL_INPUT_ONE_INTEGRATION = 1 , CONTROL_INPUT_TWO_INTEGRATION = 2 , CONTROL_INPUT_SIZE = 3 } |
Define the type of input expected by the robot. More... | |
enum | Representation_t { SE3Representation , R3xSO3Representation } |
Enum used to specify what difference operation is used in FeaturePose. More... | |
Functions | |
void | sotDEBUGF (const int, const char *,...) |
void | sotDEBUGF (const char *,...) |
void | sotERRORF (const int, const char *,...) |
void | sotERRORF (const char *,...) |
std::ostream & | __null_stream () |
void | sotTDEBUGF (const int, const char *,...) |
void | sotTDEBUGF (const char *,...) |
template<typename T > | |
Vector6d | convertVelocity (const MatrixHomogeneous &M, const MatrixHomogeneous &Mdes, const Vector &faNufafbDes) |
void | toVector (const MatrixHomogeneous &M, Vector7 &v) |
Vector7 | toVector (const MatrixHomogeneous &M) |
template<> | |
Vector6d | convertVelocity< SE3_t > (const MatrixHomogeneous &M, const MatrixHomogeneous &Mdes, const Vector &faNufafbDes) |
template<> | |
Vector6d | convertVelocity< R3xSO3_t > (const MatrixHomogeneous &M, const MatrixHomogeneous &Mdes, const Vector &faNufafbDes) |
void | buildFrom (const MatrixHomogeneous &MH, MatrixTwist &MT) |
SOT_CORE_EXPORT std::ostream & | operator<< (std::ostream &os, const VectorMultiBound &v) |
SOT_CORE_EXPORT std::istream & | operator>> (std::istream &os, VectorMultiBound &v) |
RobotUtilShrPtr | RefVoidRobotUtil () |
RobotUtilShrPtr | getRobotUtil (std::string &robotName) |
bool | isNameInRobotUtil (std::string &robotName) |
RobotUtilShrPtr | createRobotUtil (std::string &robotName) |
std::shared_ptr< std::vector< std::string > > | getListOfRobots () |
bool | base_se3_to_sot (ConstRefVector pos, ConstRefMatrix R, RefVector q_sot) |
Variables | |
SOT_CORE_EXPORT DebugTrace | sotDEBUGFLOW |
SOT_CORE_EXPORT DebugTrace | sotERRORFLOW |
const std::string | ControlInput_s [] = {"noInteg", "oneInteg", "twoInteg"} |
This is the namespace for a subset of helperd classes related to the implementation of the Stack-Of-Tasks.
typedef const Eigen::Map<const MatrixRXd> dynamicgraph::sot::const_SigMatrixXd |
typedef const Eigen::Map<const Eigen::VectorXd> dynamicgraph::sot::const_SigVectorXd |
typedef const Eigen::Ref<const Eigen::MatrixXd> dynamicgraph::sot::ConstRefMatrix |
typedef const Eigen::Ref<const Eigen::VectorXd>& dynamicgraph::sot::ConstRefVector |
typedef Eigen::VectorXd::Index dynamicgraph::sot::Index |
typedef Mailbox<dynamicgraph::Vector> dynamicgraph::sot::MailboxVector |
typedef Eigen::Matrix<double, 6, 6> SOT_CORE_EXPORT dynamicgraph::sot::MatrixForce |
typedef Eigen::Transform<double, 3, Eigen::Affine> SOT_CORE_EXPORT dynamicgraph::sot::MatrixHomogeneous |
typedef Eigen::Matrix<double, 3, 3> SOT_CORE_EXPORT dynamicgraph::sot::MatrixRotation |
typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> dynamicgraph::sot::MatrixRXd |
typedef Eigen::Matrix<double, 6, 6> SOT_CORE_EXPORT dynamicgraph::sot::MatrixTwist |
typedef Eigen::Quaternion<double> SOT_CORE_EXPORT dynamicgraph::sot::Quaternion |
typedef Eigen::Map<Quaternion> SOT_CORE_EXPORT dynamicgraph::sot::QuaternionMap |
typedef pinocchio::CartesianProductOperation< pinocchio::VectorSpaceOperationTpl<3, double>, pinocchio::SpecialOrthogonalOperationTpl<3, double> > dynamicgraph::sot::R3xSO3_t |
typedef Eigen::Ref<Eigen::MatrixXd> dynamicgraph::sot::RefMatrix |
typedef Eigen::Ref<Eigen::VectorXd> dynamicgraph::sot::RefVector |
typedef std::shared_ptr<RobotUtil> dynamicgraph::sot::RobotUtilShrPtr |
Accessors - This should be changed to RobotUtilPtrShared.
typedef pinocchio::SpecialEuclideanOperationTpl<3, double> dynamicgraph::sot::SE3_t |
typedef Eigen::Map<MatrixRXd> dynamicgraph::sot::SigMatrixXd |
typedef Eigen::Map<Eigen::VectorXd> dynamicgraph::sot::SigVectorXd |
typedef Eigen::Matrix<double, 7, 1> SOT_CORE_EXPORT dynamicgraph::sot::Vector7 |
typedef std::vector<MultiBound> dynamicgraph::sot::VectorMultiBound |
typedef Eigen::Quaternion<double> SOT_CORE_EXPORT dynamicgraph::sot::VectorQuaternion |
typedef Eigen::Vector3d SOT_CORE_EXPORT dynamicgraph::sot::VectorRollPitchYaw |
typedef Eigen::Vector3d SOT_CORE_EXPORT dynamicgraph::sot::VectorRotation |
typedef Eigen::AngleAxis<double> SOT_CORE_EXPORT dynamicgraph::sot::VectorUTheta |
Enum used to specify what difference operation is used in FeaturePose.
Enumerator | |
---|---|
SE3Representation | |
R3xSO3Representation |
|
inline |
bool dynamicgraph::sot::base_se3_to_sot | ( | ConstRefVector | pos, |
ConstRefMatrix | R, | ||
RefVector | q_sot | ||
) |
|
inline |
Vector6d dynamicgraph::sot::convertVelocity | ( | const MatrixHomogeneous & | M, |
const MatrixHomogeneous & | Mdes, | ||
const Vector & | faNufafbDes | ||
) |
Vector6d dynamicgraph::sot::convertVelocity< R3xSO3_t > | ( | const MatrixHomogeneous & | M, |
const MatrixHomogeneous & | Mdes, | ||
const Vector & | faNufafbDes | ||
) |
Vector6d dynamicgraph::sot::convertVelocity< SE3_t > | ( | const MatrixHomogeneous & | M, |
const MatrixHomogeneous & | Mdes, | ||
const Vector & | faNufafbDes | ||
) |
RobotUtilShrPtr dynamicgraph::sot::createRobotUtil | ( | std::string & | robotName | ) |
std::shared_ptr<std::vector<std::string> > dynamicgraph::sot::getListOfRobots | ( | ) |
RobotUtilShrPtr dynamicgraph::sot::getRobotUtil | ( | std::string & | robotName | ) |
bool dynamicgraph::sot::isNameInRobotUtil | ( | std::string & | robotName | ) |
SOT_CORE_EXPORT std::ostream& dynamicgraph::sot::operator<< | ( | std::ostream & | os, |
const VectorMultiBound & | v | ||
) |
SOT_CORE_EXPORT std::istream& dynamicgraph::sot::operator>> | ( | std::istream & | os, |
VectorMultiBound & | v | ||
) |
RobotUtilShrPtr dynamicgraph::sot::RefVoidRobotUtil | ( | ) |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Vector7 dynamicgraph::sot::toVector | ( | const MatrixHomogeneous & | M | ) |
void dynamicgraph::sot::toVector | ( | const MatrixHomogeneous & | M, |
Vector7 & | v | ||
) |
const std::string dynamicgraph::sot::ControlInput_s[] = {"noInteg", "oneInteg", "twoInteg"} |
|
extern |
|
extern |