Classes | Enumerations | Functions | Variables
RdlTwoLegModelTests.cpp File Reference
#include <gtest/gtest.h>
#include "UnitTestUtils.hpp"
#include <iostream>
#include "rdl_dynamics/Model.h"
#include "rdl_dynamics/Contacts.h"
#include "rdl_dynamics/Dynamics.h"
#include "rdl_dynamics/Kinematics.h"
Include dependency graph for RdlTwoLegModelTests.cpp:

Go to the source code of this file.

Classes

struct  RdlTwoLegModelTests
 

Enumerations

enum  COMNames {
  COMHip, COMThigh, COMShank, COMFoot,
  COMNameLast
}
 
enum  ControlNames {
  ControlRightThighRotZ, ControlRightKneeRotZ, ControlRightAnkleRotZ, ControlLeftThighRotZ,
  ControlLeftKneeRotZ, ControlLeftAnkleRotZ, ControlNameLast
}
 
enum  JointLocations { JointLocationHip = 0, JointLocationKnee, JointLocationAnkle, JointLocationLast }
 
enum  ParamNames { ParamSteplength = 0, ParamNameLast }
 
enum  PosNames {
  PosHipPosX, PosHipPosY, PosHipRotZ, PosRightThighRotZ,
  PosRightShankRotZ, PosRightAnkleRotZ, PosLeftThighRotZ, PosLeftShankRotZ,
  PosLeftAnkleRotZ, PosNameLast
}
 
enum  RGyrationNames {
  RGyrationHip, RGyrationThigh, RGyrationShank, RGyrationFoot,
  RGyrationLast
}
 
enum  SegmentLengthsNames {
  SegmentLengthsHip = 0, SegmentLengthsThigh, SegmentLengthsShank, SegmentLengthsFootHeight,
  SegmentLengthsFoot, SegmentLengthsNameLast
}
 
enum  SegmentMassNames {
  SegmentMassHip, SegmentMassThigh, SegmentMassShank, SegmentMassFoot,
  SegmentMassLast
}
 
enum  StateNames {
  StateHipPosX, StateHipPosY, StateHipRotZ, StateRightThighRotZ,
  StateRightShankRotZ, StateRightAnkleRotZ, StateLeftThighRotZ, StateLeftShankRotZ,
  StateLeftAnkleRotZ, StateHipVelX, StateHipVelY, StateHipRotVelZ,
  StateRightThighRotVelZ, StateRightShankRotVelZ, StateRightAnkleRotVelZ, StateLeftThighRotVelZ,
  StateLeftShankRotVelZ, StateLeftAnkleRotVelZ, StateNameLast
}
 

Functions

template<typename T >
void copy_values (T *dest, const T *src, size_t count)
 
void init_model (Model *model)
 
int main (int argc, char **argv)
 
 TEST (RdlTwoLegModelTests, TestForwardDynamicsContactsDirectFootmodel)
 
 TEST (RdlTwoLegModelTests, TestClearContactsInertiaMatrix)
 

Variables

Vector3d com_position [COMNameLast]
 
ConstraintSet constraint_set_both
 
ConstraintSet constraint_set_left
 
ConstraintSet constraint_set_left_flat
 
ConstraintSet constraint_set_right
 
Body foot_left_body
 
unsigned int foot_left_id
 
Body foot_right_body
 
unsigned int foot_right_id
 
Vector3d heel_point (0., 0., 0.)
 
Body hip_body
 
unsigned int hip_id
 
Vector3d joint_location [JointLocationLast] = { Vector3d(0., 0., 0.), Vector3d(0., -0.2425 * ModelHeight, 0.), Vector3d(0., -0.2529 * ModelHeight, 0.) }
 
Joint joint_rot_z (SpatialVector(0., 0., 1., 0., 0., 0.))
 
Joint joint_txtyrz (SpatialVector(0., 0., 0., 1., 0., 0.), SpatialVector(0., 0., 0., 0., 1., 0.), SpatialVector(0., 0., 1., 0., 0., 0.))
 
Body lower_leg_left_body
 
unsigned int lower_leg_left_id
 
Body lower_leg_right_body
 
unsigned int lower_leg_right_id
 
Vector3d medial_point (0., 0., 0.)
 
const double ModelHeight = 1.741
 
const double ModelMass = 73.
 
VectorNd Q
 
VectorNd QDDot
 
VectorNd QDot
 
Vector3d rgyration [RGyrationLast]
 
double segment_lengths [SegmentLengthsNameLast] = { 0.4346, 0.4222, 0.4340, 0.0317, 0.2581 }
 
double segment_mass [SegmentMassLast] = { 0.4346 * ModelMass, 0.1416 * ModelMass, 0.0433 * ModelMass, 0.0137 * ModelMass }
 
VectorNd Tau
 
const double TEST_PREC = 1.0e-13
 
Body upper_leg_left_body
 
unsigned int upper_leg_left_id
 
Body upper_leg_right_body
 
unsigned int upper_leg_right_id
 

Enumeration Type Documentation

enum COMNames
Enumerator
COMHip 
COMThigh 
COMShank 
COMFoot 
COMNameLast 

Definition at line 130 of file RdlTwoLegModelTests.cpp.

Enumerator
ControlRightThighRotZ 
ControlRightKneeRotZ 
ControlRightAnkleRotZ 
ControlLeftThighRotZ 
ControlLeftKneeRotZ 
ControlLeftAnkleRotZ 
ControlNameLast 

Definition at line 82 of file RdlTwoLegModelTests.cpp.

Enumerator
JointLocationHip 
JointLocationKnee 
JointLocationAnkle 
JointLocationLast 

Definition at line 109 of file RdlTwoLegModelTests.cpp.

enum ParamNames
Enumerator
ParamSteplength 
ParamNameLast 

Definition at line 39 of file RdlTwoLegModelTests.cpp.

enum PosNames
Enumerator
PosHipPosX 
PosHipPosY 
PosHipRotZ 
PosRightThighRotZ 
PosRightShankRotZ 
PosRightAnkleRotZ 
PosLeftThighRotZ 
PosLeftShankRotZ 
PosLeftAnkleRotZ 
PosNameLast 

Definition at line 45 of file RdlTwoLegModelTests.cpp.

Enumerator
RGyrationHip 
RGyrationThigh 
RGyrationShank 
RGyrationFoot 
RGyrationLast 

Definition at line 142 of file RdlTwoLegModelTests.cpp.

Enumerator
SegmentLengthsHip 
SegmentLengthsThigh 
SegmentLengthsShank 
SegmentLengthsFootHeight 
SegmentLengthsFoot 
SegmentLengthsNameLast 

Definition at line 93 of file RdlTwoLegModelTests.cpp.

Enumerator
SegmentMassHip 
SegmentMassThigh 
SegmentMassShank 
SegmentMassFoot 
SegmentMassLast 

Definition at line 119 of file RdlTwoLegModelTests.cpp.

enum StateNames
Enumerator
StateHipPosX 
StateHipPosY 
StateHipRotZ 
StateRightThighRotZ 
StateRightShankRotZ 
StateRightAnkleRotZ 
StateLeftThighRotZ 
StateLeftShankRotZ 
StateLeftAnkleRotZ 
StateHipVelX 
StateHipVelY 
StateHipRotVelZ 
StateRightThighRotVelZ 
StateRightShankRotVelZ 
StateRightAnkleRotVelZ 
StateLeftThighRotVelZ 
StateLeftShankRotVelZ 
StateLeftAnkleRotVelZ 
StateNameLast 

Definition at line 59 of file RdlTwoLegModelTests.cpp.

Function Documentation

template<typename T >
void copy_values ( T *  dest,
const T *  src,
size_t  count 
)

Definition at line 246 of file RdlTwoLegModelTests.cpp.

void init_model ( Model model)

Definition at line 157 of file RdlTwoLegModelTests.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 374 of file RdlTwoLegModelTests.cpp.

TEST ( RdlTwoLegModelTests  ,
TestForwardDynamicsContactsDirectFootmodel   
)

Definition at line 251 of file RdlTwoLegModelTests.cpp.

TEST ( RdlTwoLegModelTests  ,
TestClearContactsInertiaMatrix   
)

Definition at line 317 of file RdlTwoLegModelTests.cpp.

Variable Documentation

Vector3d com_position[COMNameLast]
Initial value:
= { Vector3d(0., 0.3469 * ModelHeight, 0.), Vector3d(0., 0.2425 * ModelHeight, 0.), Vector3d(0., 0.2529 * ModelHeight, 0.),
Vector3d(0.0182 * ModelHeight, 0., 0.) }
const double ModelHeight

Definition at line 139 of file RdlTwoLegModelTests.cpp.

ConstraintSet constraint_set_both

Definition at line 37 of file RdlTwoLegModelTests.cpp.

ConstraintSet constraint_set_left

Definition at line 35 of file RdlTwoLegModelTests.cpp.

ConstraintSet constraint_set_left_flat

Definition at line 36 of file RdlTwoLegModelTests.cpp.

ConstraintSet constraint_set_right

Definition at line 34 of file RdlTwoLegModelTests.cpp.

Body foot_left_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int foot_left_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Body foot_right_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int foot_right_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Vector3d heel_point(0., 0., 0.)
Body hip_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int hip_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Vector3d joint_location[JointLocationLast] = { Vector3d(0., 0., 0.), Vector3d(0., -0.2425 * ModelHeight, 0.), Vector3d(0., -0.2529 * ModelHeight, 0.) }

Definition at line 117 of file RdlTwoLegModelTests.cpp.

Joint joint_rot_z(SpatialVector(0., 0., 1., 0., 0., 0.))
Joint joint_txtyrz(SpatialVector(0., 0., 0., 1., 0., 0.), SpatialVector(0., 0., 0., 0., 1., 0.), SpatialVector(0., 0., 1., 0., 0., 0.))
Body lower_leg_left_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int lower_leg_left_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Body lower_leg_right_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int lower_leg_right_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Vector3d medial_point(0., 0., 0.)
const double ModelHeight = 1.741

Definition at line 104 of file RdlTwoLegModelTests.cpp.

const double ModelMass = 73.

Definition at line 103 of file RdlTwoLegModelTests.cpp.

Definition at line 29 of file RdlTwoLegModelTests.cpp.

VectorNd QDDot

Definition at line 31 of file RdlTwoLegModelTests.cpp.

VectorNd QDot

Definition at line 30 of file RdlTwoLegModelTests.cpp.

Vector3d rgyration[RGyrationLast]
Initial value:
= { Vector3d(0.1981, 0.1021, 0.1848), Vector3d(0.1389, 0.0629, 0.1389), Vector3d(0.1123, 0.0454, 0.1096),
Vector3d(0.0081, 0.0039, 0.0078) }

Definition at line 151 of file RdlTwoLegModelTests.cpp.

double segment_lengths[SegmentLengthsNameLast] = { 0.4346, 0.4222, 0.4340, 0.0317, 0.2581 }

Definition at line 107 of file RdlTwoLegModelTests.cpp.

double segment_mass[SegmentMassLast] = { 0.4346 * ModelMass, 0.1416 * ModelMass, 0.0433 * ModelMass, 0.0137 * ModelMass }

Definition at line 128 of file RdlTwoLegModelTests.cpp.

VectorNd Tau

Definition at line 32 of file RdlTwoLegModelTests.cpp.

const double TEST_PREC = 1.0e-13

Definition at line 16 of file RdlTwoLegModelTests.cpp.

Body upper_leg_left_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int upper_leg_left_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.

Body upper_leg_right_body

Definition at line 24 of file RdlTwoLegModelTests.cpp.

unsigned int upper_leg_right_id

Definition at line 22 of file RdlTwoLegModelTests.cpp.



rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:28