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

Namespaces

 id
 

Classes

class  BaseMotionConstraint
 Keeps the 6D base motion in a specified range. More...
 
class  BaseNodes
 Node variables used to construct the base motion spline. More...
 
struct  BaseState
 Can represent the 6Degree-of-Freedom floating base of a robot. More...
 
class  CentroidalModel
 Centroidal Dynamics model relating forces to base accelerations. More...
 
class  CubicHermitePolynomial
 Represents a Cubic-Hermite-Polynomial. More...
 
class  DynamicConstraint
 Ensure that the optimized motion complies with the system dynamics. More...
 
class  DynamicModel
 A interface for the the system dynamics of a legged robot. More...
 
class  EulerConverter
 Converts Euler angles and derivatives to angular quantities. More...
 
class  ForceConstraint
 Ensures foot force that is unilateral and inside friction cone. More...
 
class  HeightMap
 Holds the height and slope of the terrain. More...
 
class  KinematicModel
 Contains all the robot specific kinematic parameters. More...
 
class  LinearEqualityConstraint
 Calculates the constraint violations for linear constraints. More...
 
class  NlpFactory
 
class  Node
 A node represents the state of a trajectory at a specific time. More...
 
class  NodeCost
 Assigns a cost to node values. More...
 
class  Nodes
 Position and velocity of nodes used to generate a Hermite spline. More...
 
class  NodesObserver
 Base class to receive up-to-date values of the NodeVariables. More...
 
class  NodeSpline
 A spline built from node values and fixed polynomial durations. More...
 
struct  Parameters
 Holds the parameters to tune the optimization problem. More...
 
class  PhaseDurations
 A variable set composed of the phase durations of an endeffector. More...
 
class  PhaseDurationsObserver
 Base class to receive up-to-date values of the ContactSchedule. More...
 
class  PhaseNodes
 Nodes that are associated to either swing or stance phases. More...
 
class  PhaseSpline
 A spline built from node values and polynomial durations. More...
 
class  Polynomial
 A polynomial of arbitrary order and dimension. More...
 
class  RangeOfMotionConstraint
 Constrains an endeffector to lie in a box around the nominal stance. More...
 
struct  RobotModel
 Holds pointers to the robot specific kinematics and dynamics. More...
 
class  SoftConstraint
 Converts a constraint to a cost by weighing the quadratic violations. More...
 
class  Spline
 A spline built from a sequence of cubic polynomials. More...
 
class  SplineAccConstraint
 Ensures continuous accelerations between polynomials. More...
 
struct  SplineHolder
 Holds pointers to fully constructed splines, that are linked to the optimization variables. More...
 
class  State
 Stores at state comprised of values and higher-order derivatives. More...
 
class  SwingConstraint
 Constrains the foot position during the swing-phase. More...
 
class  TerrainConstraint
 Ensures the endeffectors always lays on or above terrain height. More...
 
class  TimeDiscretizationConstraint
 Constraints evaluated at discretized times along a trajectory. More...
 
class  TotalDurationConstraint
 Makes sure all the phase durations sum up to the total time. More...
 
class  TOWR
 TOWR - Trajectory Optimizer for Walking Robots. More...
 

Typedefs

using VectorXd = Eigen::VectorXd
 

Enumerations

enum  ConstraintName {
  Dynamic, EndeffectorRom, TotalTime, Terrain,
  Force, Swing, BaseRom, BaseAcc
}
 
enum  CostName { ForcesCostID }
 
enum  Dim2D { X_ =0, Y_ }
 
enum  Dim3D { X =0, Y, Z }
 
enum  Dim6D {
  AX =0, AY, AZ, LX,
  LY, LZ
}
 
enum  Dx { kPos =0, kVel, kAcc, kJerk }
 < the values or derivative. For motions e.g. position, velocity, ... More...
 

Functions

static Eigen::Matrix3d BuildInertiaTensor (double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz)
 
std::vector< PhaseNodes::PolyInfoBuildPolyInfos (int phase_count, bool is_in_contact_at_start, int n_polys_in_changing_phase, PhaseNodes::Type type)
 
CentroidalModel::Jac Cross (const Eigen::Vector3d &in)
 
 TEST (CentroidalDynamicsTest, GetBaseAcceleration)
 
 TEST (CentroidalDynamicsTest, GetJacobianOfAccWrtBase)
 
 TEST (DynamicConstraintTest, EigenScalar)
 
 TEST (CentroidalDynamicsTest, TestRotations)
 
static Dim2D To2D (Dim3D dim)
 

Variables

static const Dim6D AllDim6D [] = {AX, AY, AZ, LX, LY, LZ}
 
static constexpr int k2D = 2
 
static constexpr int k3D = 3
 
static constexpr int k6D = 6
 

Typedef Documentation

using towr::VectorXd = typedef Eigen::VectorXd

Definition at line 35 of file dynamic_constraint_test.cc.

Enumeration Type Documentation

Enumerator
Dynamic 
EndeffectorRom 
TotalTime 
Terrain 
Force 
Swing 
BaseRom 
BaseAcc 

Definition at line 38 of file parameters.h.

Enumerator
ForcesCostID 

Definition at line 40 of file parameters.h.

Enumerator
X_ 
Y_ 

Definition at line 45 of file cartesian_dimensions.h.

Enumerator

Definition at line 49 of file cartesian_dimensions.h.

Enumerator
AX 
AY 
AZ 
LX 
LY 
LZ 

Definition at line 59 of file cartesian_dimensions.h.

enum towr::Dx

< the values or derivative. For motions e.g. position, velocity, ...

Enumerator
kPos 
kVel 
kAcc 
kJerk 

Definition at line 41 of file state.h.

Function Documentation

static Eigen::Matrix3d towr::BuildInertiaTensor ( double  Ixx,
double  Iyy,
double  Izz,
double  Ixy,
double  Ixz,
double  Iyz 
)
static

Definition at line 36 of file centroidal_model.cc.

std::vector<PhaseNodes::PolyInfo> towr::BuildPolyInfos ( int  phase_count,
bool  is_in_contact_at_start,
int  n_polys_in_changing_phase,
PhaseNodes::Type  type 
)

Definition at line 36 of file phase_nodes.cc.

CentroidalModel::Jac towr::Cross ( const Eigen::Vector3d &  in)

Definition at line 48 of file centroidal_model.cc.

towr::TEST ( CentroidalDynamicsTest  ,
GetBaseAcceleration   
)

Definition at line 36 of file centroidal_dynamics_test.cc.

towr::TEST ( CentroidalDynamicsTest  ,
GetJacobianOfAccWrtBase   
)

Definition at line 54 of file centroidal_dynamics_test.cc.

towr::TEST ( DynamicConstraintTest  ,
EigenScalar   
)

Definition at line 69 of file dynamic_constraint_test.cc.

towr::TEST ( CentroidalDynamicsTest  ,
TestRotations   
)

Definition at line 76 of file centroidal_dynamics_test.cc.

static Dim2D towr::To2D ( Dim3D  dim)
static

Definition at line 50 of file cartesian_dimensions.h.

Variable Documentation

const Dim6D towr::AllDim6D[] = {AX, AY, AZ, LX, LY, LZ}
static

Definition at line 60 of file cartesian_dimensions.h.

constexpr int towr::k2D = 2
static

Definition at line 44 of file cartesian_dimensions.h.

constexpr int towr::k3D = 3
static

Definition at line 48 of file cartesian_dimensions.h.

constexpr int towr::k6D = 6
static

Definition at line 58 of file cartesian_dimensions.h.



towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:57