Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
pSim Class Reference

Main class for forward dynamics computation. More...

#include <psim.h>

Inheritance diagram for pSim:
Inheritance graph
[legend]

Public Member Functions

int AutoSchedule (int max_procs)
 Automatic scheduling for max_procs processors. More...
 
virtual void Clear ()
 
int ConstraintForces (fVec &cf)
 Extract the constraint forces. More...
 
void DumpSchedule (ostream &ost)
 Dump the schedule information to ost. More...
 
void GetPJoint (Joint *_joint, pJoint *_pjoints[2])
 
int NumLeaves ()
 
 pSim ()
 Default constructor. More...
 
int Schedule ()
 Creates default schedule, which is optimized for serial computation. More...
 
int Schedule (Joint **joints)
 Creates a schedule that assembles the chain in the specified order of joints. More...
 
int ScheduleDepth ()
 
int TotalCost ()
 Approximate indicators of total computational cost. More...
 
int Update ()
 Compute joint accelerations. More...
 
int Update (double timestep, std::vector< class SDContactPair * > &sdContactPairs)
 Compute joint accelerations and contact forces. More...
 
 ~pSim ()
 
- Public Member Functions inherited from Chain
void add_scale_object (const scale_object &_s)
 
int AddJoint (Joint *target, Joint *p)
 Add a new joint target as a child of joint p. More...
 
int AddJoint (Joint *target, const char *parent_name, const char *charname=0)
 Add a new joint target as a child of joint with name parent_name. More...
 
JointAddJoint (JointData *joint_data, const char *charname=0)
 Create and add a joint using JointData structure. More...
 
JointAddRoot (const char *name=0, const fVec3 &grav=fVec3(0.0, 0.0, 9.8))
 Add the (unique) root joint. More...
 
int AddRoot (Joint *r)
 Add the (unique) root joint. More...
 
void ApplyGeomScale (SceneGraph *sg)
 
int BeginCreateChain (int append=false)
 Indicates begining of creating a kinematic chain. More...
 
void CalcAcceleration ()
 
void CalcPosition ()
 Forward kinematics. More...
 
void CalcVelocity ()
 
 Chain ()
 
void clear_scale_object_list ()
 
int ClearExtForce ()
 Clear the external forces/torques. More...
 
int ClearJointForce ()
 Clear the joint forces/torques. More...
 
double ComJacobian (fMat &J, fVec3 &com, const char *chname=0)
 Computes the com Jacobian. More...
 
int Connect (Joint *virtual_joint, Joint *parent_joint)
 Connect two links by adding a new virtual joint. More...
 
int CreateParallel (int num_char, const char *prmname, const char *charname, const fVec3 &init_pos=0.0, const fMat33 &init_att=1.0, const fVec3 &pos_offset=0.0, const fMat33 &att_offset=1.0, int init_num=0)
 Automatically generate multiple identical chains. More...
 
int CreateSerial (int num_joint, const JointData &joint_data, const char *charname=0, Joint *parent_joint=0)
 Automatically generate a serial chain. More...
 
int Disconnect (Joint *j)
 Disconnect the loop at the specified virtual joint. More...
 
int EndCreateChain (SceneGraph *sg=NULL)
 End editing a chain. More...
 
JointFindCharacterRoot (const char *charname)
 Find the root joint of the character with name charname. More...
 
JointFindJoint (const char *jname, const char *charname=0)
 Find a joint from name. More...
 
JointFindJoint (int _id)
 Find a joint with ID _id. More...
 
int GetJointAcc (fVec &accs)
 
int GetJointForce (fVec &forces)
 Obtain the joint forces/torques. More...
 
int GetJointList (Joint **&joints)
 Obtain a list of pointers to all joints. More...
 
int GetJointNameList (char **&jnames)
 Obtain a list of joint names. More...
 
int GetJointValue (fVec &values)
 Obtain the joint values/velocities/accelerations. More...
 
int GetJointVel (fVec &vels)
 
int Integrate (double timestep)
 Performs Euler integration with timestep timestep [s]. More...
 
int IntegrateAdaptive (double &timestep, int step, double min_timestep=DEFAULT_MIN_TIMESTEP, double max_integ_error=DEFAULT_MAX_INTEG_ERROR)
 Performs Euler integration with adaptive timestep. More...
 
int IntegrateRK4 (double timestep, int step)
 Performs 4-th order Runge-Kutta integration. More...
 
int IntegrateRK4Value (double timestep, int step)
 
int IntegrateRK4Velocity (double timestep, int step)
 
int IntegrateValue (double timestep)
 Integrate value/velocity only. More...
 
int IntegrateVelocity (double timestep)
 
void InvDyn (fVec &tau)
 Inverse dynamics. More...
 
int Load (const char *fname, const char *charname=0)
 Load the chain from a file in original (*.prm) format. More...
 
int LoadXML (const char *fname, const char *charname=0)
 Load the chain from an XML file. More...
 
int NumDOF ()
 Total degrees of freedom. More...
 
int NumJoint ()
 Total number of joints. More...
 
int NumValue ()
 Dimension of the joint value vector (using Euler parameter representation for orientation). More...
 
int RemoveJoint (Joint *j)
 disconnect joint j from its parent More...
 
JointRoot ()
 
int Save (const char *fname, const char *charname=0) const
 Save the chain data to a file in original (*.prm) format. More...
 
int Save (ostream &ost, const char *charname=0) const
 
int SaveStatus (fVec &value, fVec &vel, fVec &acc)
 Save current joint values, velocities, and accelerations. More...
 
int SaveXML (const char *fname, const char *charname=0) const
 Save the chain data to a file in XML format. More...
 
int SaveXML (ostream &ost, const char *charname=0) const
 
int set_abs_position_orientation (Joint *jnt, const fVec3 &abs_pos, const fMat33 &abs_att)
 
int SetAllTorqueGiven (int _tg)
 Change torque/motion control property of all joints. More...
 
int SetCharacterTorqueGiven (const char *charname, int _tg)
 Change torque/motion control property of a character. More...
 
int SetJointAcc (const fVec &accs)
 
int SetJointForce (const fVec &forces)
 Set all joint forces/torques. More...
 
int SetJointValue (const fVec &values)
 Set all joint values. More...
 
int SetJointVel (const fVec &vels)
 Set all joint velocities/accelerations. More...
 
int SetStatus (const fVec &value, const fVec &vel, const fVec &acc)
 Set current joint values, velocities, and accelerations. More...
 
int SetTorqueGiven (Joint *_joint, int _tg)
 Change torque/motion control property of a joint. More...
 
double TotalCOM (fVec3 &com, const char *chname=0)
 Center of mass of the chain. More...
 
virtual ~Chain ()
 

Protected Member Functions

virtual int clear_contact ()
 
virtual int clear_data ()
 Clear arrays only; don't delete joints. More...
 
virtual int init (SceneGraph *sg)
 Initialize the parameters. More...
 
int init_contact ()
 
int myinit ()
 
- Protected Member Functions inherited from Chain
void _apply_scale (Joint *jnt, double scale)
 
void apply_geom_scale (SceneGraph *sg, Joint *cur)
 
virtual void apply_scale ()
 
void apply_scale (const scale_object &_s)
 
void apply_scale_sub (Joint *cur, double scale)
 
void apply_scale_top (Joint *top, double scale)
 
void calc_abs_positions (Joint *cur, SceneGraph *sg)
 
void calc_rel_positions (Joint *cur, SceneGraph *sg)
 
void init_scale (SceneGraph *sg)
 
void init_scale_sub (Node *node)
 
void reset_scale ()
 
void reset_scale_sub (Joint *jnt)
 
void set_all_torque_given (Joint *cur, int _tg)
 
void set_relative_positions (SceneGraph *sg)
 

Private Member Functions

int build_subchain_tree (int _n_joints, Joint **joints, subchain_list &buf)
 
void build_subchain_tree (Joint *cur_joint, subchain_list &buf)
 
void calc_consts ()
 
void calc_dvel ()
 
void col_disassembly ()
 
int contact_vjoint_index (Joint *_jnt)
 
pSubChaindefault_schedule (pSubChain *p, Joint *j)
 
void default_schedule_virtual (Joint *j)
 
void disassembly ()
 
int in_subchain (pSubChain *sc, pLink *pl)
 
void setup_pjoint (Joint *j)
 
void setup_pjoint_virtual (Joint *j)
 
void update_collision ()
 
void update_position ()
 
void update_velocity ()
 

Private Attributes

std::vector< fVec3all_jdot_r
 
std::vector< fVec3all_jdot_v
 
std::vector< fMatall_Jr
 
std::vector< fMatall_Jv
 
joint_list all_vjoints
 
fVec3 cone_dir [N_FRIC_CONE_DIV]
 
std::vector< fVec3contact_relvels
 
joint_list contact_vjoints
 
std::vector< double > fric_coefs
 
JointInfojoint_info
 
pSubChainsubchains
 

Friends

class pJoint
 
class pLink
 
class pSubChain
 

Additional Inherited Members

- Protected Attributes inherited from Chain
double ** all_value
 Pointers to the integration variables. More...
 
double ** all_value_dot
 
double ** all_vel
 
double ** all_vel_dot
 
int do_connect
 true after Connect() was called; application (or subclass) must reset the flag More...
 
int in_create_chain
 true if between BeginCreateChain() and EndCreateChain(). More...
 
double * init_value
 
double * init_vel
 
double * j_acc_p [4]
 
double * j_value_dot [4]
 for 4-th order Runge-Kutta More...
 
int n_dof
 
int n_joint
 
int n_thrust
 total DOF of the joints with t_given = false More...
 
int n_value
 
Jointroot
 Chain information. More...
 
std::list< scale_objectscale_object_list
 

Detailed Description

Main class for forward dynamics computation.

Definition at line 446 of file psim.h.

Constructor & Destructor Documentation

pSim::pSim ( )
inline

Default constructor.

Default constructor.

Parameters
_rankRank of the process on which the instance is generated (only for parallel processing).

Definition at line 461 of file psim.h.

pSim::~pSim ( )
inline

Definition at line 482 of file psim.h.

Member Function Documentation

int pSim::AutoSchedule ( int  max_procs)

Automatic scheduling for max_procs processors.

Definition at line 765 of file schedule.cpp.

int pSim::build_subchain_tree ( int  _n_joints,
Joint **  joints,
subchain_list buf 
)
private

Definition at line 1352 of file schedule.cpp.

void pSim::build_subchain_tree ( Joint cur_joint,
subchain_list buf 
)
private

Definition at line 1363 of file schedule.cpp.

void pSim::calc_consts ( )
private

Definition at line 286 of file psim.cpp.

void pSim::calc_dvel ( )
private

Definition at line 574 of file update.cpp.

void pSim::Clear ( )
virtual

Clear

Reimplemented from Chain.

Definition at line 87 of file psim.cpp.

int pSim::clear_contact ( )
protectedvirtual

Definition at line 123 of file psim.cpp.

int pSim::clear_data ( )
protectedvirtual

Clear arrays only; don't delete joints.

Reimplemented from Chain.

Definition at line 105 of file psim.cpp.

void pSim::col_disassembly ( )
private

Definition at line 676 of file update.cpp.

int pSim::ConstraintForces ( fVec cf)

Extract the constraint forces.

psim.cpp Create: Katsu Yamane, 04.02.23

Definition at line 17 of file psim.cpp.

int pSim::contact_vjoint_index ( Joint _jnt)
inlineprivate

Definition at line 589 of file psim.h.

pSubChain * pSim::default_schedule ( pSubChain p,
Joint j 
)
private

Definition at line 1072 of file schedule.cpp.

void pSim::default_schedule_virtual ( Joint j)
private

Definition at line 1117 of file schedule.cpp.

void pSim::disassembly ( )
private

disassembly

Definition at line 1155 of file update.cpp.

void pSim::DumpSchedule ( ostream &  ost)

Dump the schedule information to ost.

Definition at line 336 of file psim.cpp.

void pSim::GetPJoint ( Joint _joint,
pJoint _pjoints[2] 
)
inline

Definition at line 544 of file psim.h.

int pSim::in_subchain ( pSubChain sc,
pLink pl 
)
private

Definition at line 1407 of file schedule.cpp.

int pSim::init ( SceneGraph *  sg)
protectedvirtual

Initialize the parameters.

Reimplemented from Chain.

Definition at line 218 of file psim.cpp.

int pSim::init_contact ( )
protected

Init

Definition at line 173 of file psim.cpp.

int pSim::myinit ( )
protected

Definition at line 231 of file psim.cpp.

int pSim::NumLeaves ( )

Definition at line 65 of file psim.cpp.

int pSim::Schedule ( )

Creates default schedule, which is optimized for serial computation.

default schedule: most efficient for serial computation

Definition at line 1060 of file schedule.cpp.

int pSim::Schedule ( Joint **  joints)

Creates a schedule that assembles the chain in the specified order of joints.

manual schedule: specify the order

Definition at line 1336 of file schedule.cpp.

int pSim::ScheduleDepth ( )

Definition at line 51 of file psim.cpp.

void pSim::setup_pjoint ( Joint j)
private

Definition at line 243 of file psim.cpp.

void pSim::setup_pjoint_virtual ( Joint j)
private

Definition at line 265 of file psim.cpp.

int pSim::TotalCost ( )

Approximate indicators of total computational cost.

Definition at line 34 of file psim.cpp.

int pSim::Update ( )

Compute joint accelerations.

Definition at line 40 of file update.cpp.

int pSim::Update ( double  timestep,
std::vector< class SDContactPair * > &  sdContactPairs 
)

Compute joint accelerations and contact forces.

Compute joint accelerations and contact forces. Contact forces are computed such that the relative velocity becomes zero after timestep [s].

Parameters
[in]timestepTimestep of the integration.
[in]sdContactPairsPointer to the ColInfo object containing the contact information.
void pSim::update_collision ( )
private

collision

Definition at line 568 of file update.cpp.

void pSim::update_position ( )
private

position-dependent

Definition at line 146 of file update.cpp.

void pSim::update_velocity ( )
private

velocity-dependent

Definition at line 768 of file update.cpp.

Friends And Related Function Documentation

friend class pJoint
friend

Definition at line 449 of file psim.h.

friend class pLink
friend

Definition at line 450 of file psim.h.

friend class pSubChain
friend

Definition at line 451 of file psim.h.

Member Data Documentation

std::vector<fVec3> pSim::all_jdot_r
private

Definition at line 585 of file psim.h.

std::vector<fVec3> pSim::all_jdot_v
private

Definition at line 584 of file psim.h.

std::vector<fMat> pSim::all_Jr
private

Definition at line 583 of file psim.h.

std::vector<fMat> pSim::all_Jv
private

Definition at line 582 of file psim.h.

joint_list pSim::all_vjoints
private

Definition at line 581 of file psim.h.

fVec3 pSim::cone_dir[N_FRIC_CONE_DIV]
private

Definition at line 587 of file psim.h.

std::vector<fVec3> pSim::contact_relvels
private

Definition at line 578 of file psim.h.

joint_list pSim::contact_vjoints
private

Definition at line 577 of file psim.h.

std::vector<double> pSim::fric_coefs
private

Definition at line 579 of file psim.h.

JointInfo* pSim::joint_info
private

Definition at line 602 of file psim.h.

pSubChain* pSim::subchains
private

Definition at line 603 of file psim.h.


The documentation for this class was generated from the following files:


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:43