momentumopt
|
Classes | |
class | Clock |
Helper class to measure time required to run an optimization procedure. More... | |
class | ContactPlanFromFile |
This class implements the ContactPlanInterface by reading a sequence of contacts from a configuration file. More... | |
class | ContactPlanInterface |
This class implements a simple interface to store a sequence of contacts, including its activation and de-activation time, position and orientation of the contact, and a variable (set to 1) indicating if the forces at this contact are subject to friction cone constraints or (set to 2) if not, such as in the case of hands grasping bars. More... | |
class | ContactSequence |
This class is a container for a sequence of contact states, for all end-effectors. More... | |
class | ContactState |
This class is a container for all variables required to define a contact state: position and orientation of the contact, time of activation and de-activation of the contact, and a ContactType variable indicating whether, forces are subject to a friction cone (ContactType::FlatContact) or not (ContactType::FullContact) such as in the case of a hand grasping a bar. More... | |
class | DynamicsFeedback |
Class that implements the dynamic description of momentum dynamics as an optimal control problem, to be used by an LQR algorithm to derive a feedback sequence. More... | |
class | DynamicsFeedbackWrapper |
class | DynamicsOptimizer |
class | DynamicsSequence |
This class is a container for a sequence of dynamic states, for all time steps in the optimization. More... | |
struct | DynamicsState |
This class is a container for all variables required to define a dynamic state: center of mass position, linear and angular momenta and its rates; forces, torques and center of pressure of the end- effectors; positions, orientations, activations and contact types of each end-effector. More... | |
struct | FrictionCone |
Helper class to define a linear approximation of a friction cone. More... | |
class | Interpolator |
class | KinematicsInterface |
class | KinematicsOptimizer |
class | KinematicsSequence |
This class is a container for a sequence of kinematic states. More... | |
class | KinematicsState |
This class is a container for all variables required to define a kinematics state: joint posture, joint velocities and accelerations, endeffector poses and momentum. More... | |
class | PlannerSetting |
struct | Problem |
Helper structure used to define common functionality and naming conventions. More... | |
class | PyKinematicsInterface |
class | RobotAcceleration |
class | RobotPosture |
class | RobotVelocity |
class | TerrainDescription |
This class is a container for a terrain description in terms of terrain surfaces. More... | |
class | TerrainRegion |
This class is a container for all variables required to define a terrain region. More... | |
class | TrajectoryGenerator |
class | ViapointSequence |
This class is a container for a sequence of viapoint states for all end-effectors. More... | |
class | ViapointState |
This class defines a viapoint state including position and orientation. More... | |
Typedefs | |
typedef Eigen::Matrix< double, 4, 4 > | Matrix4 |
typedef Eigen::Transform< double, 3, Eigen::Affine > | Transform |
Enumerations | |
enum | ContactType { FreeContact = 0, FlatContact = 1, FullContact = 2 } |
Definition of contact type: FlatContact: forces subject to friction cone constrains of flat surface FullContact: forces free in any direction (e.g. More... | |
enum | PlannerIntParam { PlannerIntParam_NumDofs, PlannerIntParam_NumTimesteps, PlannerIntParam_NumViapoints, PlannerIntParam_NumJointViapoints, PlannerIntParam_NumActiveDofs, PlannerIntParam_MaxNumTimeIterations, PlannerIntParam_NumExtendedActiveDofs, PlannerIntParam_NumActiveEndeffectors, PlannerIntParam_MaxKinTrajectoryIterations, PlannerIntParam_MaxKinConvergenceIterations, PlannerIntParam_NumSubsamples, PlannerIntParam_KinDynIterations } |
enum | PlannerBoolParam { PlannerBoolParam_IsTimeHorizonFixed, PlannerBoolParam_IsFrictionConeLinear, PlannerBoolParam_DisplayMotion, PlannerBoolParam_LoadKinematics, PlannerBoolParam_StoreData, PlannerBoolParam_UseDefaultSolverSetting } |
enum | PlannerDoubleParam { PlannerDoubleParam_Gravity, PlannerDoubleParam_TimeStep, PlannerDoubleParam_RobotMass, PlannerDoubleParam_RobotWeight, PlannerDoubleParam_TimeHorizon, PlannerDoubleParam_MinRelHeight, PlannerDoubleParam_MassTimesGravity, PlannerDoubleParam_FrictionCoefficient, PlannerDoubleParam_MaxTimeResidualTolerance, PlannerDoubleParam_MinTimeResidualImprovement, PlannerDoubleParam_WeightArmTorque, PlannerDoubleParam_WeightLegTorque, PlannerDoubleParam_WeightTimePenalty, PlannerDoubleParam_WeightTimeRegularization, PlannerDoubleParam_FloorHeight, PlannerDoubleParam_KinSlacksPenalty, PlannerDoubleParam_KinIntegrationStep, PlannerDoubleParam_LambdaRegularization, PlannerDoubleParam_KinConvergenceTolerance, PlannerDoubleParam_SwingTrajViaZ, PlannerDoubleParam_WeightLinMomentumTracking, PlannerDoubleParam_WeightAngMomentumTracking, PlannerDoubleParam_WeightEndEffContact, PlannerDoubleParam_WeightEndEffTracking, PlannerDoubleParam_PGainEndEffTracking, PlannerDoubleParam_PGainComTracking, PlannerDoubleParam_WeightJointReg, PlannerDoubleParam_PGainOrientationTracking } |
enum | PlannerStringParam { PlannerStringParam_ConfigFile, PlannerStringParam_SaveDynamicsFile, PlannerStringParam_SaveKinematicsFile, PlannerStringParam_DefaultSolverSettingFile } |
enum | PlannerIntVectorParam { PlannerIntVectorParam_ActiveDofs, PlannerIntVectorParam_ExtendedActiveDofs } |
enum | PlannerVectorParam { PlannerVectorParam_TimeRange, PlannerVectorParam_TorqueRange, PlannerVectorParam_ExternalForce, PlannerVectorParam_GravityVector, PlannerVectorParam_CenterOfMassMotion, PlannerVectorParam_MaxEndeffectorLengths, PlannerVectorParam_WeightArmForce, PlannerVectorParam_WeightLegForce, PlannerVectorParam_WeightArmForceRate, PlannerVectorParam_WeightLegForceRate, PlannerVectorParam_WeightCenterOfMass, PlannerVectorParam_WeightLinearMomentum, PlannerVectorParam_WeightAngularMomentum, PlannerVectorParam_WeightLinearMomentumRate, PlannerVectorParam_WeightAngularMomentumRate, PlannerVectorParam_WeightFinalLinearMomentum, PlannerVectorParam_WeightCenterOfMassViapoint, PlannerVectorParam_WeightFinalAngularMomentum, PlannerVectorParam_WeightDynamicTrackingCenterOfMass, PlannerVectorParam_WeightDynamicTrackingLinearMomentum, PlannerVectorParam_WeightDynamicTrackingAngularMomentum, PlannerVectorParam_MinJointAngles, PlannerVectorParam_MaxJointAngles, PlannerVectorParam_KinematicDefaultJointPositions, PlannerVectorParam_WeightJointVelocity, PlannerVectorParam_WeightJointAcceleration, PlannerVectorParam_WeightKinematicTrackingCenterOfMass, PlannerVectorParam_WeightKinematicDefaultJointPositions, PlannerVectorParam_WeightKinematicTrackingLinearMomentum, PlannerVectorParam_WeightKinematicTrackingAngularMomentum, PlannerVectorParam_WeightKinematicTrackingBaseOrientation, PlannerVectorParam_WeightKinematicTrackingLinearMomentumRate, PlannerVectorParam_WeightKinematicTrackingAngularMomentumRate, PlannerVectorParam_WeightKinematicTrackingEndeffectorPosition, PlannerVectorParam_WeightKinematicTrackingNonActiveEndeffectorPosition } |
enum | PlannerArrayParam { PlannerArrayParam_EndeffectorOffset, PlannerArrayParam_CenterOfPressureRange } |
enum | PlannerCVectorParam { PlannerCVectorParam_Viapoints, PlannerCVectorParam_JointViapoints } |
enum | Heuristic { TrustRegion, SoftConstraint, TimeOptimization } |
enum | InterpolationMethod { PiecewiseLinear, PiecewiseConstant } |
Functions | |
ContactType | idToContactType (int cnt_type_id) |
Eigen::Vector3d | orientationError (const Eigen::Quaternion< double > &desired_orientation, const Eigen::Quaternion< double > ¤t_orientation) |
computes the error between two quaternions by rotating the desired orientation back by the current orientation, and taking the logarithm of the result. | |
Eigen::Vector3d | requiredAngularVelocity (const Eigen::Quaternion< double > &desired_orientation, const Eigen::Quaternion< double > ¤t_orientation, const double &time_step, bool in_body_coordinates=false) |
computation of the required angular velocity to move from a current orientation to a desired orientation in a given time interval. More... | |
Eigen::Quaternion< double > | integrateAngularVelocity (const Eigen::Quaternion< double > ¤t_orientation, const Eigen::Vector3d &angular_velocity, const double &time_step, bool in_body_coordinates=false) |
integration of a quaternion given an angular velocity given either in body or world coordinates and a time interval for integration | |
Eigen::Matrix3d | skewMatrix (const Eigen::Vector3d &vec) |
Eigen::Vector3d | logarithmicMap (const Eigen::Quaternion< double > &quaternion) |
Eigen::Quaternion< double > | exponentialMap (const Eigen::Vector3d &rotation_vector) |
Eigen::Matrix4d | toQuaternionMatrix (const Eigen::Quaternion< double > &quaternion, bool is_conjugate) |
Eigen::Matrix< double, 4, 3 > | jacobianQuaternionWrtRotationVector (const Eigen::Vector3d &rotation_vector) |
Eigen::Matrix3d | jacobianAngularVelocityWrtRotationVector (const Eigen::Vector3d &rotation_vector) |
Eigen::Vector3d | toAngularVelocity (const Eigen::Vector3d &rotation_vector, const Eigen::Vector3d &rotation_vector_rates, bool in_body_coordinates) |
Eigen::Vector3d | fromAngularVelocity (const Eigen::Vector3d &rotation_vector, const Eigen::Vector3d &angular_velocity, bool in_body_coordinates) |
Use ipython run display.py -i <path_to_datafile>
Computes gains using lqr in the end_effector space for solo (assumes legs are weightless) and performs a backward pass to compute gains using a trajectory
Computes gains using lqr in the end_effector space for solo (assumes legs are weightless) and performs a backward pass to compute gains using a trajectory
Computes gains using lqr in the end_effector space for solo (assumes legs are weightless) and performs a backward pass to compute gains using a trajectory
|
strong |
Definition of contact type: FlatContact: forces subject to friction cone constrains of flat surface FullContact: forces free in any direction (e.g.
hand grasp)
Available array variables used by the planner
Available boolean variables used by the planner
Available c-vector variables used by the planner
Available double variables used by the planner
Available integer variables used by the planner
Available vector variables used by the planner
Available string variables used by the planner
Available vector variables used by the planner
Eigen::Vector3d momentumopt::requiredAngularVelocity | ( | const Eigen::Quaternion< double > & | desired_orientation, |
const Eigen::Quaternion< double > & | current_orientation, | ||
const double & | time_step, | ||
bool | in_body_coordinates = false |
||
) |
computation of the required angular velocity to move from a current orientation to a desired orientation in a given time interval.
Angular velocity can be returned in body or world coordinates.