Forward dynamics computation based on Assembly-Disassembly Algorithm. More...


Go to the source code of this file.
Classes | |
| struct | JointInfo |
| class | pJoint |
| Class for representing "handle"; two pJoint instances are attached to both sides of each joint. More... | |
| class | pLink |
| Class for representing a single link in a schedule tree. More... | |
| class | pSim |
| Main class for forward dynamics computation. More... | |
| class | pSubChain |
| Node for schedule tree; represents a partial chain. More... | |
Macros | |
| #define | N_FRIC_CONE_DIV 8 |
| Number of vertices of the friction cone approximation. More... | |
Typedefs | |
| typedef std::vector< Joint * > | joint_list |
| typedef std::vector< class pJoint * > | p_joint_list |
| typedef std::list< class pSubChain * > | subchain_list |
Enumerations | |
| enum | PSIM_AXIS { PSIM_AXIS_NULL = -1, PSIM_AXIS_X, PSIM_AXIS_Y, PSIM_AXIS_Z, PSIM_AXIS_RX, PSIM_AXIS_RY, PSIM_AXIS_RZ } |
Forward dynamics computation based on Assembly-Disassembly Algorithm.
Definition in file psim.h.
| #define N_FRIC_CONE_DIV 8 |
| typedef std::vector<Joint*> joint_list |
| typedef std::vector<class pJoint*> p_joint_list |
| typedef std::list<class pSubChain*> subchain_list |
| enum PSIM_AXIS |