Namespaces | |
command | |
core | |
detail | |
internal | |
Classes | |
class | __sotDebug_init |
class | AbstractSotExternalInterface |
struct | AdderVariadic |
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 |
struct | BinaryOpHeader |
struct | BoolOp |
class | CausalFilter |
class | ClampWorkspace |
class | CoMFreezer |
struct | Comparison |
struct | Composer |
class | Contiifstream |
class | ControlGR |
class | ControlPD |
struct | ConvolutionTemporal |
class | DebugTrace |
class | Derivator |
class | Device |
struct | Diagonalizer |
class | DoubleConstant |
class | Event |
class | ExceptionAbstract |
class | ExceptionDynamic |
class | ExceptionFactory |
class | ExceptionFeature |
class | ExceptionSignal |
class | ExceptionTask |
class | ExceptionTools |
class | ExpMovingAvg |
class | ExtractJointMimics |
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 | 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 | FeaturePose |
Feature that controls the relative (or absolute) pose between two frames A (or world) and B. More... | |
class | FeaturePosture |
class | FeatureReferenceHelper |
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 |
struct | FootUtil |
struct | ForceLimits |
struct | ForceUtil |
class | GainAdaptive |
class | GainHyperbolic |
Hyperbolic gain. It follows the law
The default coefficients are: 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 |
struct | HandUtil |
class | Header |
struct | HomoToMatrix |
struct | HomoToRotation |
struct | HomoToTwist |
class | Integrator |
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... | |
struct | Inverser |
struct | InverserQuaternion |
struct | InverserRotation |
class | JointLimitator |
Filter control vector to avoid exceeding joint maximum values. More... | |
struct | JointLimits |
class | JointTrajectoryPoint |
class | Kalman |
class | Latch |
class | MadgwickAHRS |
class | Mailbox |
struct | MailboxTimestampedObject |
struct | MatrixColumnSelector |
struct | MatrixComparison |
class | MatrixConstant |
struct | MatrixHomoToPose |
struct | MatrixHomoToPoseQuaternion |
struct | MatrixHomoToPoseRollPitchYaw |
struct | MatrixHomoToPoseUTheta |
struct | MatrixHomoToSE3Vector |
struct | MatrixSelector |
struct | MatrixToHomo |
struct | MatrixToQuaternion |
struct | MatrixToRPY |
struct | MatrixToUTheta |
struct | MatrixTranspose |
class | MemoryTaskSOT |
class | MotionPeriod |
class | MultiBound |
struct | Multiplier |
struct | Multiplier_FxE__E |
class | NamedVector |
class | NeckLimitation |
struct | Normalize |
class | OpPointModifier |
Compute position and jacobian of a local frame attached to a joint. More... | |
class | ParameterServer |
class | PeriodicCall |
class | PeriodicCallEntity |
class | PoolStorage |
This singleton class keep tracks of all features and tasks. More... | |
struct | PoseQuaternionToMatrixHomo |
struct | PoseRollPitchYawToMatrixHomo |
struct | PoseRollPitchYawToPoseUTheta |
struct | PoseUThetaToMatrixHomo |
struct | QuaternionToMatrix |
struct | QuaternionToRPY |
class | RobotSimu |
struct | RobotUtil |
struct | RPYToMatrix |
struct | RPYToQuaternion |
class | RulesJointTrajectory |
struct | SE3VectorToMatrixHomo |
class | Segment |
class | Sequencer |
struct | SkewSymToVector |
class | SmoothReach |
class | Sot |
This class implements the Stack of Task. It allows to deal with the priority of the controllers through the shell. More... | |
class | SotJointTrajectoryEntity |
This object handles trajectory of quantities and publish them as signals. More... | |
class | SotLoader |
This class is loading the control part of the Stack-Of-Tasks. More... | |
struct | Substraction |
class | Switch |
Switch. More... | |
class | Task |
Class that defines the basic elements of a task. More... | |
class | TaskAbstract |
class | TaskConti |
class | TaskPD |
class | TaskUnilateral |
class | TimeStamp |
class | timestamp |
class | Trajectory |
struct | TypeNameHelper |
class | UnaryOp |
struct | UnaryOpHeader |
struct | UThetaToQuaternion |
class | VariadicAbstract |
class | VariadicOp |
struct | VariadicOpHeader |
struct | VectorComponent |
class | VectorConstant |
struct | VectorMix |
struct | VectorSelecter |
struct | VectorStack |
class | VisualPointProjecter |
struct | WeightedAdder |
Enumerations | |
enum | ControlInput { POSITION_CONTROL = 0, VELOCITY_CONTROL = 1, TORQUE_CONTROL = 2, CONTROL_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... | |
Variables | |
__sotDebug_init | __sotDebug_initialisator |
const std::string | ControlInput_s [] = {"noInteg", "oneInteg", "twoInteg"} |
std::ofstream | debugfile |
double | |
Matrix | |
static std::map< std::string, RobotUtilShrPtr > | sgl_map_name_to_robot_util |
SOT_CORE_EXPORT DebugTrace | sotDEBUGFLOW |
SOT_CORE_EXPORT DebugTrace | sotERRORFLOW |
vec_double | |
Vector | |
ForceLimits | VoidForceLimits |
JointLimits | VoidJointLimits |
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 |
Definition at line 66 of file matrix-geometry.hh.
typedef const Eigen::Map<const Eigen::VectorXd> dynamicgraph::sot::const_SigVectorXd |
Definition at line 67 of file matrix-geometry.hh.
typedef const Eigen::Ref<const Eigen::MatrixXd> dynamicgraph::sot::ConstRefMatrix |
Definition at line 72 of file matrix-geometry.hh.
typedef const Eigen::Ref<const Eigen::VectorXd>& dynamicgraph::sot::ConstRefVector |
Definition at line 70 of file matrix-geometry.hh.
Definition at line 38 of file abstract-sot-external-interface.hh.
Define EntityClassName here rather than in the header file so that it can be used by the macros DEFINE_SIGNAL_**_FUNCTION.
Definition at line 49 of file filter-differentiator.cpp.
Definition at line 169 of file feature-pose.hh.
Definition at line 170 of file feature-pose.hh.
typedef Eigen::VectorXd::Index dynamicgraph::sot::Index |
Definition at line 39 of file robot-utils.hh.
Definition at line 45 of file mailbox-vector.hh.
typedef Eigen::Matrix<double, 6, 6> SOT_CORE_EXPORT dynamicgraph::sot::MatrixForce |
Definition at line 81 of file matrix-geometry.hh.
typedef Eigen::Transform<double, 3, Eigen::Affine> SOT_CORE_EXPORT dynamicgraph::sot::MatrixHomogeneous |
Definition at line 75 of file matrix-geometry.hh.
typedef Eigen::Matrix<double, 3, 3> SOT_CORE_EXPORT dynamicgraph::sot::MatrixRotation |
Definition at line 76 of file matrix-geometry.hh.
typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> dynamicgraph::sot::MatrixRXd |
Definition at line 63 of file matrix-geometry.hh.
typedef Eigen::Matrix<double, 6, 6> SOT_CORE_EXPORT dynamicgraph::sot::MatrixTwist |
Definition at line 82 of file matrix-geometry.hh.
Definition at line 575 of file operator.hh.
typedef Multiplier_FxE__E<dynamicgraph::Matrix, dynamicgraph::Vector> dynamicgraph::sot::Multiplier_matrix_vector |
Definition at line 577 of file operator.hh.
typedef Multiplier_FxE__E<MatrixHomogeneous, dynamicgraph::Vector> dynamicgraph::sot::Multiplier_matrixHomo_vector |
Definition at line 579 of file operator.hh.
typedef Multiplier_FxE__E<MatrixTwist, dynamicgraph::Vector> dynamicgraph::sot::Multiplier_matrixTwist_vector |
Definition at line 581 of file operator.hh.
typedef Eigen::Quaternion<double> SOT_CORE_EXPORT dynamicgraph::sot::Quaternion |
Definition at line 85 of file matrix-geometry.hh.
typedef Eigen::Map<Quaternion> SOT_CORE_EXPORT dynamicgraph::sot::QuaternionMap |
Definition at line 86 of file matrix-geometry.hh.
typedef pinocchio::CartesianProductOperation< pinocchio::VectorSpaceOperationTpl<3, double>, pinocchio::SpecialOrthogonalOperationTpl<3, double> > dynamicgraph::sot::R3xSO3_t |
Definition at line 44 of file test_feature_generic.cpp.
typedef Eigen::Ref<Eigen::MatrixXd> dynamicgraph::sot::RefMatrix |
Definition at line 71 of file matrix-geometry.hh.
typedef Eigen::Ref<Eigen::VectorXd> dynamicgraph::sot::RefVector |
Definition at line 69 of file matrix-geometry.hh.
typedef std::shared_ptr<RobotUtil> dynamicgraph::sot::RobotUtilShrPtr |
Accessors - This should be changed to RobotUtilPtrShared.
Definition at line 299 of file robot-utils.hh.
Definition at line 45 of file test_feature_generic.cpp.
Definition at line 37 of file abstract-sot-external-interface.hh.
typedef Eigen::Map<MatrixRXd> dynamicgraph::sot::SigMatrixXd |
Definition at line 64 of file matrix-geometry.hh.
typedef Eigen::Map<Eigen::VectorXd> dynamicgraph::sot::SigVectorXd |
Definition at line 65 of file matrix-geometry.hh.
typedef Switch<bool, int> dynamicgraph::sot::SwitchBool |
Definition at line 29 of file switch.cpp.
Definition at line 35 of file switch.cpp.
typedef Switch<Vector, int> dynamicgraph::sot::SwitchVector |
Definition at line 23 of file switch.cpp.
typedef Vector6d dynamicgraph::sot::Vector6 |
Definition at line 27 of file madgwickahrs.cpp.
typedef Eigen::Matrix<double, 7, 1> SOT_CORE_EXPORT dynamicgraph::sot::Vector7 |
Definition at line 84 of file matrix-geometry.hh.
typedef std::vector<MultiBound> dynamicgraph::sot::VectorMultiBound |
Definition at line 71 of file multi-bound.hh.
Definition at line 78 of file matrix-geometry.hh.
typedef Eigen::Vector3d SOT_CORE_EXPORT dynamicgraph::sot::VectorRollPitchYaw |
Definition at line 80 of file matrix-geometry.hh.
typedef Eigen::Vector3d SOT_CORE_EXPORT dynamicgraph::sot::VectorRotation |
Definition at line 79 of file matrix-geometry.hh.
Definition at line 77 of file matrix-geometry.hh.
Enum used to specify what difference operation is used in FeaturePose.
Enumerator | |
---|---|
SE3Representation | |
R3xSO3Representation |
Definition at line 29 of file feature-pose.hh.
bool dynamicgraph::sot::base_se3_to_sot | ( | ConstRefVector | pos, |
ConstRefMatrix | R, | ||
RefVector | q_sot | ||
) |
Definition at line 444 of file robot-utils.cpp.
bool dynamicgraph::sot::base_sot_to_urdf | ( | ConstRefVector | q_sot, |
RefVector | q_urdf | ||
) |
Definition at line 482 of file robot-utils.cpp.
bool dynamicgraph::sot::base_urdf_to_sot | ( | ConstRefVector | q_urdf, |
RefVector | q_sot | ||
) |
Definition at line 470 of file robot-utils.cpp.
|
inline |
Definition at line 88 of file matrix-geometry.hh.
Vector6d dynamicgraph::sot::convertVelocity | ( | const MatrixHomogeneous & | M, |
const MatrixHomogeneous & | Mdes, | ||
const Vector & | faNufafbDes | ||
) |
RobotUtilShrPtr dynamicgraph::sot::createRobotUtil | ( | std::string & | robotName | ) |
Definition at line 535 of file robot-utils.cpp.
dynamicgraph::sot::DEFINE_SIGNAL_INNER_FUNCTION | ( | x_dx_ddx | , |
dynamicgraph::Vector | |||
) |
Definition at line 120 of file filter-differentiator.cpp.
dynamicgraph::sot::DEFINE_SIGNAL_OUT_FUNCTION | ( | imu_quat | , |
dynamicgraph::Vector | |||
) |
Definition at line 101 of file madgwickahrs.cpp.
dynamicgraph::sot::DEFINE_SIGNAL_OUT_FUNCTION | ( | x_filtered | , |
dynamicgraph::Vector | |||
) |
*************************************************************** /// The following signals depend only on other inner signals, so they just need to copy the interested part of the inner signal they depend on. *************************************************************** ///
Definition at line 136 of file filter-differentiator.cpp.
dynamicgraph::sot::DEFINE_SIGNAL_OUT_FUNCTION | ( | dx | , |
dynamicgraph::Vector | |||
) |
Definition at line 145 of file filter-differentiator.cpp.
dynamicgraph::sot::DEFINE_SIGNAL_OUT_FUNCTION | ( | ddx | , |
dynamicgraph::Vector | |||
) |
Definition at line 154 of file filter-differentiator.cpp.
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | Latch | , |
"Latch" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | RobotSimu | , |
"RobotSimu" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | DoubleConstant | , |
"DoubleConstant" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | VisualPointProjecter | , |
"VisualPointProjecter" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | ExpMovingAvg | , |
"ExpMovingAvg" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | GradientAscent | , |
"GradientAscent" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | Kalman | , |
"Kalman" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | SwitchVector | , |
"SwitchVector" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | SwitchBool | , |
"SwitchBoolean" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | Event | , |
"Event" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | SwitchMatrixHomogeneous | , |
"SwitchMatrixHomogeneous" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | MadgwickAHRS | , |
"MadgwickAHRS" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | Segment | , |
"Segment" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | ParameterServer | , |
"ParameterServer" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | FilterDifferentiator | , |
"FilterDifferentiator" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | Integrator | , |
"Integrator" | |||
) |
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN | ( | FeaturePosture | , |
"FeaturePosture" | |||
) |
std::string dynamicgraph::sot::force_default_rtn | ( | "Force name not found" | ) |
std::shared_ptr< std::vector< std::string > > dynamicgraph::sot::getListOfRobots | ( | ) |
Definition at line 507 of file robot-utils.cpp.
RobotUtilShrPtr dynamicgraph::sot::getRobotUtil | ( | std::string & | robotName | ) |
Definition at line 521 of file robot-utils.cpp.
bool dynamicgraph::sot::isNameInRobotUtil | ( | std::string & | robotName | ) |
Definition at line 528 of file robot-utils.cpp.
std::string dynamicgraph::sot::joint_default_rtn | ( | "Joint name not found" | ) |
std::ostream & dynamicgraph::sot::operator<< | ( | std::ostream & | os, |
const VectorMultiBound & | v | ||
) |
Definition at line 228 of file multi-bound.cpp.
ostream& dynamicgraph::sot::operator<< | ( | ostream & | os, |
const ExceptionAbstract & | error | ||
) |
Definition at line 77 of file exception-abstract.cpp.
std::ostream& dynamicgraph::sot::operator<< | ( | std::ostream & | os, |
const Flags & | fl | ||
) |
std::ostream& dynamicgraph::sot::operator<< | ( | std::ostream & | os, |
const MultiBound & | m | ||
) |
Definition at line 146 of file multi-bound.cpp.
std::istream & dynamicgraph::sot::operator>> | ( | std::istream & | os, |
VectorMultiBound & | v | ||
) |
Definition at line 238 of file multi-bound.cpp.
std::istream& dynamicgraph::sot::operator>> | ( | std::istream & | is, |
Flags & | fl | ||
) |
std::istream& dynamicgraph::sot::operator>> | ( | std::istream & | is, |
MultiBound & | m | ||
) |
Definition at line 170 of file multi-bound.cpp.
RobotUtilShrPtr dynamicgraph::sot::RefVoidRobotUtil | ( | ) |
Definition at line 44 of file robot-utils.cpp.
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Multiplier_double_vector | , |
Multiply_double_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Multiplier_matrix_vector | , |
Multiply_matrix_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Multiplier_matrixHomo_vector | , |
Multiply_matrixHomo_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Multiplier_matrixTwist_vector | , |
Multiply_matrixTwist_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Substraction< dynamicgraph::Matrix > | , |
Substract_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Substraction< dynamicgraph::Vector > | , |
Substract_of_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Substraction< double > | , |
Substract_of_double | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | VectorStack | , |
Stack_of_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Composer | , |
Compose_R_and_T | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | ConvolutionTemporal | , |
ConvolutionTemporal | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | Comparison< double > | , |
CompareDouble | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | MatrixComparison< Vector > | , |
CompareVector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | WeightedAdder< dynamicgraph::Matrix > | , |
WeightAdd_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | WeightedAdder< dynamicgraph::Vector > | , |
WeightAdd_of_vector | |||
) |
dynamicgraph::sot::REGISTER_BINARY_OP | ( | WeightedAdder< double > | , |
WeightAdd_of_double | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | VectorSelecter | , |
Selec_of_vector | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | VectorComponent | , |
Component_of_vector | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixSelector | , |
Selec_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixColumnSelector | , |
Selec_column_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixTranspose | , |
MatrixTranspose | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | Diagonalizer | , |
MatrixDiagonal | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | Inverser< MatrixHomogeneous > | , |
Inverse_of_matrixHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | Inverser< MatrixTwist > | , |
Inverse_of_matrixtwist | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | Normalize | , |
Norm_of_vector | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | InverserRotation | , |
Inverse_of_matrixrotation | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | InverserQuaternion | , |
Inverse_of_unitquat | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixHomoToPoseUTheta | , |
MatrixHomoToPoseUTheta | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixHomoToSE3Vector | , |
MatrixHomoToSE3Vector | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | SE3VectorToMatrixHomo | , |
SE3VectorToMatrixHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | SkewSymToVector | , |
SkewSymToVector | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | PoseUThetaToMatrixHomo | , |
PoseUThetaToMatrixHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixHomoToPoseQuaternion | , |
MatrixHomoToPoseQuaternion | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | PoseQuaternionToMatrixHomo | , |
PoseQuaternionToMatrixHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixHomoToPoseRollPitchYaw | , |
MatrixHomoToPoseRollPitchYaw | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | PoseRollPitchYawToMatrixHomo | , |
PoseRollPitchYawToMatrixHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | PoseRollPitchYawToPoseUTheta | , |
PoseRollPitchYawToPoseUTheta | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | HomoToMatrix | , |
HomoToMatrix | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixToHomo | , |
MatrixToHomo | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | HomoToTwist | , |
HomoToTwist | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | HomoToRotation | , |
HomoToRotation | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixHomoToPose | , |
MatrixHomoToPose | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | RPYToMatrix | , |
RPYToMatrix | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixToRPY | , |
MatrixToRPY | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | RPYToQuaternion | , |
RPYToQuaternion | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | QuaternionToRPY | , |
QuaternionToRPY | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | QuaternionToMatrix | , |
QuaternionToMatrix | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixToQuaternion | , |
MatrixToQuaternion | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | MatrixToUTheta | , |
MatrixToUTheta | |||
) |
dynamicgraph::sot::REGISTER_UNARY_OP | ( | UThetaToQuaternion | , |
UThetaToQuaternion | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | VectorMix | , |
Mix_of_vector | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | AdderVariadic< Matrix > | , |
Add_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | AdderVariadic< Vector > | , |
Add_of_vector | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | AdderVariadic< double > | , |
Add_of_double | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< Matrix > | , |
Multiply_of_matrix | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< Vector > | , |
Multiply_of_vector | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< MatrixRotation > | , |
Multiply_of_matrixrotation | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< MatrixHomogeneous > | , |
Multiply_of_matrixHomo | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< MatrixTwist > | , |
Multiply_of_matrixtwist | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< VectorQuaternion > | , |
Multiply_of_quaternion | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | Multiplier< double > | , |
Multiply_of_double | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | BoolOp< 0 > | , |
And | |||
) |
dynamicgraph::sot::REGISTER_VARIADIC_OP | ( | BoolOp< 1 > | , |
Or | |||
) |
dynamicgraph::sot::SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN | ( | FIRFilter | , |
double | , | ||
double | , | ||
double_double | , | ||
"FIRFilter" | |||
) |
FIRFilter dynamicgraph::sot::SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN | ( | FIRFilter | , |
Vector | , | ||
Matrix | , | ||
vec_mat | , | ||
"FIRFilter" | |||
) |
dynamicgraph::sot::SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_EULER | ( | IntegratorEuler | , |
double | , | ||
double | , | ||
"IntegratorEulerDoubleDouble" | |||
) |
IntegratorEulerVectorMatrix dynamicgraph::sot::SOT_FACTORY_TEMPLATE_ENTITY_PLUGIN_EULER | ( | IntegratorEuler | , |
Vector | , | ||
double | , | ||
"IntegratorEulerVectorDouble" | |||
) |
|
inline |
|
inline |
DebugTrace dynamicgraph::sot::sotDEBUGFLOW | ( | debugfile | ) |
|
inline |
|
inline |
DebugTrace dynamicgraph::sot::sotERRORFLOW | ( | debugfile | ) |
|
inline |
|
inline |
Index dynamicgraph::sot::VoidIndex | ( | - | 1 | ) |
__sotDebug_init dynamicgraph::sot::__sotDebug_initialisator |
const std::string dynamicgraph::sot::ControlInput_s[] = {"noInteg", "oneInteg", "twoInteg"} |
IntegratorEulerVectorMatrix dynamicgraph::sot::double |
Definition at line 49 of file fir-filter.cpp.
Definition at line 45 of file integrator-euler.t.cpp.
|
static |
Definition at line 505 of file robot-utils.cpp.
DebugTrace dynamicgraph::sot::sotDEBUGFLOW(debugfile) |
DebugTrace dynamicgraph::sot::sotERRORFLOW(debugfile) |
dynamicgraph::sot::vec_double |
Definition at line 49 of file fir-filter.cpp.
Definition at line 49 of file fir-filter.cpp.
ForceLimits dynamicgraph::sot::VoidForceLimits |
Definition at line 40 of file robot-utils.cpp.
JointLimits dynamicgraph::sot::VoidJointLimits |
Definition at line 41 of file robot-utils.cpp.