Namespaces | |
namespace | id |
Identifiers (names) used for variables in the optimization problem. | |
Classes | |
class | AnymalDynamicModel |
The Dynamics of the quadruped robot ANYmal. More... | |
class | AnymalKinematicModel |
The Kinematics of the quadruped robot ANYmal. More... | |
class | BaseMotionConstraint |
Keeps the 6D base motion in a specified range. More... | |
struct | BaseState |
Can represent the 6Degree-of-Freedom floating base of a robot. More... | |
class | BipedDynamicModel |
The Dynamics of a tow-legged robot built from HyQ legs. More... | |
class | BipedGaitGenerator |
Produces the contact sequence for a variety of two-legged gaits. More... | |
class | BipedKinematicModel |
The Kinematics of a tow-legged robot built from HyQ legs. More... | |
class | Block |
Sample terrain with a step in height in x-direction. More... | |
class | Chimney |
Sample terrain with a tilted vertical wall to cross a gap. More... | |
class | ChimneyLR |
Sample terrain with two tilted vertical walls to cross a gap. 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 | FlatGround |
Sample terrain of even height. More... | |
class | ForceConstraint |
Ensures foot force that is unilateral and inside friction cone. More... | |
class | GaitGenerator |
Generates endeffector phase durations for predefined gait styles. More... | |
class | Gap |
Sample terrain with parabola-modeled gap in x-direction. More... | |
class | HeightMap |
Holds the height and slope information of the terrain. More... | |
class | HyqDynamicModel |
The Dynamics of the quadruped robot HyQ. More... | |
class | HyqKinematicModel |
The Kinematics of the quadruped robot HyQ. More... | |
class | KinematicModel |
Contains all the robot specific kinematic parameters. More... | |
class | LinearEqualityConstraint |
Calculates the constraint violations for linear constraints. More... | |
class | MonopedDynamicModel |
The Dynamics of a one-legged hopper with HyQ leg. More... | |
class | MonopedGaitGenerator |
Produces the contact sequence for a variety of one-legged gaits. More... | |
class | MonopedKinematicModel |
The Kinematics of a one-legged hopper with HyQ leg. More... | |
class | NlpFormulation |
A sample combination of variables, cost and constraints. More... | |
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 | 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... | |
class | NodesVariables |
Position and velocity of nodes used to generate a Hermite spline. More... | |
class | NodesVariablesAll |
Node variables used to construct the base motion spline. More... | |
class | NodesVariablesEEForce |
Variables fully defining the endeffector forces. More... | |
class | NodesVariablesEEMotion |
Variables fully defining the endeffector motion. More... | |
class | NodesVariablesPhaseBased |
Nodes that are associated to either swing or stance phases. More... | |
class | Parameters |
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 | PhaseSpline |
A spline built from node values and polynomial durations. More... | |
class | Polynomial |
A polynomial of arbitrary order and dimension. More... | |
class | QuadrupedGaitGenerator |
Produces the contact sequence for a variety of four-legged gaits. More... | |
class | RangeOfMotionConstraint |
Constrains an endeffector to lie in a box around the nominal stance. More... | |
struct | RobotModel |
Base class for robot specific kinematics and dynamics. More... | |
class | SingleRigidBodyDynamics |
Dynamics model relating forces to base accelerations. More... | |
class | Slope |
Sample terrain with an increasing and then decreasing slope in x-direction. 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 |
Builds splines from node values (pos/vel) and durations. More... | |
class | Stairs |
Sample terrain with a two-steps in height in x-direction. 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... | |
Enumerations | |
enum | BipedIDs { L, R } |
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... | |
enum | QuadrupedIDs { LF, RF, LH, RH } |
Functions | |
static Eigen::Matrix3d | BuildInertiaTensor (double Ixx, double Iyy, double Izz, double Ixy, double Ixz, double Iyz) |
std::vector < NodesVariablesPhaseBased::PolyInfo > | BuildPolyInfos (int phase_count, bool first_phase_constant, int n_polys_in_changing_phase) |
SingleRigidBodyDynamics::Jac | Cross (const Eigen::Vector3d &in) |
TEST (DynamicModelTest, GetBaseAcceleration) | |
TEST (DynamicConstraintTest, UpdateConstraintValues) | |
TEST (DynamicModelTest, GetJacobianOfAccWrtBase) | |
TEST (DynamicModelTest, 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 |
static const std::map < RobotModel::Robot, std::string > | robot_names |
static const std::map < HeightMap::TerrainID, std::string > | terrain_names |
enum towr::BipedIDs |
Definition at line 43 of file endeffector_mappings.h.
enum towr::Dim2D |
Definition at line 45 of file cartesian_dimensions.h.
enum towr::Dim3D |
Definition at line 49 of file cartesian_dimensions.h.
enum towr::Dim6D |
Definition at line 59 of file cartesian_dimensions.h.
enum towr::Dx |
enum towr::QuadrupedIDs |
Definition at line 44 of file endeffector_mappings.h.
static Eigen::Matrix3d towr::BuildInertiaTensor | ( | double | Ixx, |
double | Iyy, | ||
double | Izz, | ||
double | Ixy, | ||
double | Ixz, | ||
double | Iyz | ||
) | [static] |
Definition at line 36 of file single_rigid_body_dynamics.cc.
std::vector<NodesVariablesPhaseBased::PolyInfo> towr::BuildPolyInfos | ( | int | phase_count, |
bool | first_phase_constant, | ||
int | n_polys_in_changing_phase | ||
) |
Definition at line 39 of file nodes_variables_phase_based.cc.
SingleRigidBodyDynamics::Jac towr::Cross | ( | const Eigen::Vector3d & | in | ) |
Definition at line 48 of file single_rigid_body_dynamics.cc.
towr::TEST | ( | DynamicModelTest | , |
GetBaseAcceleration | |||
) |
Definition at line 36 of file dynamic_model_test.cc.
towr::TEST | ( | DynamicConstraintTest | , |
UpdateConstraintValues | |||
) |
Definition at line 40 of file dynamic_constraint_test.cc.
towr::TEST | ( | DynamicModelTest | , |
GetJacobianOfAccWrtBase | |||
) |
Definition at line 41 of file dynamic_model_test.cc.
towr::TEST | ( | DynamicModelTest | , |
TestRotations | |||
) |
Definition at line 46 of file dynamic_model_test.cc.
static Dim2D towr::To2D | ( | Dim3D | dim | ) | [static] |
Definition at line 50 of file cartesian_dimensions.h.
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.
const std::map<RobotModel::Robot, std::string> towr::robot_names [static] |
{ {RobotModel::Monoped, "Monoped"}, {RobotModel::Biped, "Biped"}, {RobotModel::Hyq, "Hyq"}, {RobotModel::Anymal, "Anymal"} }
Definition at line 85 of file robot_model.h.
const std::map<HeightMap::TerrainID, std::string> towr::terrain_names [static] |
{ {HeightMap::FlatID, "Flat" }, {HeightMap::BlockID, "Block" }, {HeightMap::StairsID, "Stairs" }, {HeightMap::GapID, "Gap" }, {HeightMap::SlopeID, "Slope" }, {HeightMap::ChimneyID, "Chimney" }, {HeightMap::ChimneyLRID, "ChimenyLR" } }
Definition at line 174 of file height_map.h.