Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
Chain Class Reference

The class representing the whole mechanism. May contain multiple characters. More...

#include <chain.h>

Inheritance diagram for Chain:
Inheritance graph
[legend]

List of all members.

Classes

struct  scale_object
 XML utility functions. More...

Public Member Functions

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.
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.
JointAddJoint (JointData *joint_data, const char *charname=0)
 Create and add a joint using JointData structure.
JointAddRoot (const char *name=0, const fVec3 &grav=fVec3(0.0, 0.0, 9.8))
 Add the (unique) root joint.
int AddRoot (Joint *r)
 Add the (unique) root joint.
void ApplyGeomScale (SceneGraph *sg)
int BeginCreateChain (int append=false)
 Indicates begining of creating a kinematic chain.
void CalcAcceleration ()
void CalcPosition ()
 Forward kinematics.
void CalcVelocity ()
 Chain ()
virtual void Clear ()
 Remove all joints and clear all parameters.
void clear_scale_object_list ()
int ClearExtForce ()
 Clear the external forces/torques.
int ClearJointForce ()
 Clear the joint forces/torques.
double ComJacobian (fMat &J, fVec3 &com, const char *chname=0)
 Computes the com Jacobian.
int Connect (Joint *virtual_joint, Joint *parent_joint)
 Connect two links by adding a new virtual joint.
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.
int CreateSerial (int num_joint, const JointData &joint_data, const char *charname=0, Joint *parent_joint=0)
 Automatically generate a serial chain.
int Disconnect (Joint *j)
 Disconnect the loop at the specified virtual joint.
int EndCreateChain (SceneGraph *sg=NULL)
 End editing a chain.
JointFindCharacterRoot (const char *charname)
 Find the root joint of the character with name charname.
JointFindJoint (const char *jname, const char *charname=0)
 Find a joint from name.
JointFindJoint (int _id)
 Find a joint with ID _id.
int GetJointAcc (fVec &accs)
int GetJointForce (fVec &forces)
 Obtain the joint forces/torques.
int GetJointList (Joint **&joints)
 Obtain a list of pointers to all joints.
int GetJointNameList (char **&jnames)
 Obtain a list of joint names.
int GetJointValue (fVec &values)
 Obtain the joint values/velocities/accelerations.
int GetJointVel (fVec &vels)
int Integrate (double timestep)
 Performs Euler integration with timestep timestep [s].
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.
int IntegrateRK4 (double timestep, int step)
 Performs 4-th order Runge-Kutta integration.
int IntegrateRK4Value (double timestep, int step)
int IntegrateRK4Velocity (double timestep, int step)
int IntegrateValue (double timestep)
 Integrate value/velocity only.
int IntegrateVelocity (double timestep)
void InvDyn (fVec &tau)
 Inverse dynamics.
int Load (const char *fname, const char *charname=0)
 Load the chain from a file in original (*.prm) format.
int LoadXML (const char *fname, const char *charname=0)
 Load the chain from an XML file.
int NumDOF ()
 Total degrees of freedom.
int NumJoint ()
 Total number of joints.
int NumValue ()
 Dimension of the joint value vector (using Euler parameter representation for orientation).
int RemoveJoint (Joint *j)
 disconnect joint j from its parent
JointRoot ()
int Save (const char *fname, const char *charname=0) const
 Save the chain data to a file in original (*.prm) format.
int Save (ostream &ost, const char *charname=0) const
int SaveStatus (fVec &value, fVec &vel, fVec &acc)
 Save current joint values, velocities, and accelerations.
int SaveXML (const char *fname, const char *charname=0) const
 Save the chain data to a file in XML format.
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.
int SetCharacterTorqueGiven (const char *charname, int _tg)
 Change torque/motion control property of a character.
int SetJointAcc (const fVec &accs)
int SetJointForce (const fVec &forces)
 Set all joint forces/torques.
int SetJointValue (const fVec &values)
 Set all joint values.
int SetJointVel (const fVec &vels)
 Set all joint velocities/accelerations.
int SetStatus (const fVec &value, const fVec &vel, const fVec &acc)
 Set current joint values, velocities, and accelerations.
int SetTorqueGiven (Joint *_joint, int _tg)
 Change torque/motion control property of a joint.
double TotalCOM (fVec3 &com, const char *chname=0)
 Center of mass of the chain.
virtual ~Chain ()

Protected Member Functions

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)
virtual int clear_data ()
 Clear arrays only; don't delete joints.
virtual int init (SceneGraph *sg)
 Initialize the parameters.
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)

Protected Attributes

double ** all_value
 Pointers to the integration variables.
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
int in_create_chain
 true if between BeginCreateChain() and EndCreateChain().
double * init_value
double * init_vel
double * j_acc_p [4]
double * j_value_dot [4]
 for 4-th order Runge-Kutta
int n_dof
int n_joint
int n_thrust
 total DOF of the joints with t_given = false
int n_value
Jointroot
 Chain information.
std::list< scale_objectscale_object_list

Friends

class Joint

Detailed Description

The class representing the whole mechanism. May contain multiple characters.

Definition at line 144 of file chain.h.


Constructor & Destructor Documentation

Definition at line 46 of file chain.cpp.

Chain::~Chain ( ) [virtual]

Definition at line 65 of file chain.cpp.


Member Function Documentation

void Chain::_apply_scale ( Joint jnt,
double  scale 
) [protected]
int Chain::AddJoint ( Joint target,
Joint p 
)

Add a new joint target as a child of joint p.

Add a new joint target as a child of joint p.

Parameters:
[in]targetthe pointer to the new joint
[in]pthe pointer to the parent joint
Returns:
0 if success and -1 otherwise

Definition at line 117 of file edit.cpp.

int Chain::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.

Add a new joint target as a child of joint p.

Parameters:
[in]targetthe pointer to the new joint
[in]parent_namename of the parent joint
[in]charnamecharacter name of the parent joint
Returns:
0 if success and -1 otherwise

Definition at line 105 of file edit.cpp.

Joint * Chain::AddJoint ( JointData joint_data,
const char *  charname = 0 
)

Create and add a joint using JointData structure.

Create and add a joint using JointData structure.

Parameters:
[in]joint_datapointer to the JointData structure
[in]charnamecharacter name
Returns:
the pointer to the new joint, NULL if failed

Definition at line 164 of file edit.cpp.

Joint * Chain::AddRoot ( const char *  name = 0,
const fVec3 grav = fVec3(0.0, 0.0, 9.8) 
)

Add the (unique) root joint.

Creates a new joint and add as the (unique) root joint.

Parameters:
[in]namename of the root joint
[in]gravgravity vector
Returns:
the pointer to the root joint; fails after the first call unless BeginCreateChain(false) is called.

Definition at line 60 of file edit.cpp.

Add the (unique) root joint.

Add the (unique) root joint from a Joint object.

Parameters:
[in]rthe pointer to the joint object
Returns:
0 if success and -1 otherwise

Definition at line 87 of file edit.cpp.

void Chain::apply_geom_scale ( SceneGraph *  sg,
Joint cur 
) [protected]

Definition at line 120 of file init.cpp.

virtual void Chain::apply_scale ( ) [protected, virtual]
void Chain::apply_scale ( const scale_object _s) [protected]
void Chain::apply_scale_sub ( Joint cur,
double  scale 
) [protected]
void Chain::apply_scale_top ( Joint top,
double  scale 
) [protected]
void Chain::ApplyGeomScale ( SceneGraph *  sg)

Definition at line 115 of file init.cpp.

int Chain::BeginCreateChain ( int  append = false)

Indicates begining of creating a kinematic chain.

Indicates begining of creating a kinematic chain. Must be called before editing the chain.

Parameters:
[in]appendIf false (default), clean up the current chain and build from scratch. Otherwise append new joints to the current chain.

Definition at line 19 of file edit.cpp.

void Chain::calc_abs_positions ( Joint cur,
SceneGraph *  sg 
) [protected]

Definition at line 251 of file edit.cpp.

void Chain::calc_rel_positions ( Joint cur,
SceneGraph *  sg 
) [protected]

Definition at line 279 of file edit.cpp.

Definition at line 75 of file fk.cpp.

Forward kinematics.

Definition at line 16 of file fk.cpp.

Definition at line 41 of file fk.cpp.

void Chain::Clear ( ) [virtual]

Remove all joints and clear all parameters.

Reimplemented in pSim.

Definition at line 87 of file chain.cpp.

int Chain::clear_data ( ) [protected, virtual]

Clear arrays only; don't delete joints.

Reimplemented in pSim.

Definition at line 127 of file vary.cpp.

Clear the external forces/torques.

Definition at line 928 of file joint.cpp.

Clear the joint forces/torques.

Definition at line 912 of file joint.cpp.

double Chain::ComJacobian ( fMat J,
fVec3 com,
const char *  chname = 0 
)

Computes the com Jacobian.

Computes the com Jacobian.

Parameters:
[out]Jcom Jacobian
[out]comcom
[in]chnamename of the character to compute com Jacobian; all joints if omitted
Returns:
the total mass

Definition at line 18 of file jacobi.cpp.

int Chain::Connect ( Joint virtual_joint,
Joint parent_joint 
)

Connect two links by adding a new virtual joint.

Definition at line 95 of file vary.cpp.

int Chain::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.

Generate num_char chains with identical structure in a prm file.

Parameters:
[in]num_charnumber of chains to generate
[in]prmnameprm file name
[in]charnamecharacter name (the actual name includes the number starting from init_num)
[in]init_posthe position offset of the first chain
[in]init_attthe orientation offset of the first chain
[in]pos_offsetthe position offset of each chain from the previous
[in]att_offsetthe orientation offset of each chain from the previous
[in]init_numthe number of the first chain
int Chain::CreateSerial ( int  num_joint,
const JointData joint_data,
const char *  charname = 0,
Joint parent_joint = 0 
)

Automatically generate a serial chain.

Generate a serial chain with num_joint joints.

Parameters:
[in]num_jointnumber of joints
[in]joint_dataJointData structure to be used as the template for the joints; each joint will named as joint_data.name + number
[in]charnamecharacter name (optional)
[in]parent_jointpointer to the root of the serial chain (optional); the global root if omitted or NULL

Disconnect the loop at the specified virtual joint.

Definition at line 111 of file vary.cpp.

int Chain::EndCreateChain ( SceneGraph *  sg = NULL)

End editing a chain.

End editing a chain; performs initialization process.

Parameters:
[in]sgthe pointer to the SceneGraph to be used for setting the initial configuration.

Definition at line 225 of file edit.cpp.

Joint * Chain::FindCharacterRoot ( const char *  charname)

Find the root joint of the character with name charname.

Definition at line 429 of file chain.cpp.

Joint * Chain::FindJoint ( const char *  jname,
const char *  charname = 0 
)

Find a joint from name.

Find a joint from name. If charname is not null, find a joint whose basename is jname and character name is charname. Otherwise, find a joint whose name is jname.

Parameters:
[in]jnamejoint name
[in]charnamecharacter name
Returns:
the pointer to the joint, NULL if not found

Definition at line 391 of file chain.cpp.

Find a joint with ID _id.

Definition at line 415 of file chain.cpp.

Definition at line 214 of file joint.cpp.

int Chain::GetJointForce ( fVec forces)

Obtain the joint forces/torques.

Definition at line 866 of file joint.cpp.

int Chain::GetJointList ( Joint **&  joints)

Obtain a list of pointers to all joints.

Obtain a list of pointers to all joints.

Returns:
number of joints

Definition at line 365 of file chain.cpp.

int Chain::GetJointNameList ( char **&  jnames)

Obtain a list of joint names.

Obtain a list of joint names.

Returns:
number of joints

Definition at line 338 of file chain.cpp.

int Chain::GetJointValue ( fVec values)

Obtain the joint values/velocities/accelerations.

Definition at line 124 of file joint.cpp.

Definition at line 172 of file joint.cpp.

int Chain::init ( SceneGraph *  sg) [protected, virtual]

Initialize the parameters.

Reimplemented in pSim, and IK.

Definition at line 22 of file init.cpp.

void Chain::init_scale ( SceneGraph *  sg) [protected]

Definition at line 92 of file init.cpp.

void Chain::init_scale_sub ( Node *  node) [protected]

Definition at line 97 of file init.cpp.

int Chain::Integrate ( double  timestep)

Performs Euler integration with timestep timestep [s].

Definition at line 110 of file integ.cpp.

int Chain::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.

Performs Euler integration with adaptive timestep. Requires two acceleration computations per step.

Parameters:
[in,out]timestepinputs maximum timestep and overwritten by the actual timestep
[in]stepstep in the integration (0/1)
[in]min_timestepminimum timestep
[in]max_integ_errormaximum error

estimate the integration error by comparing x1 and x2, where (1) x1 = x(t) + xdot(t)dt (2) x(t+dt/2) = x(t) + xdot(t)dt/2, x2 = x(t+dt/2) + xdot(t+dt/2)dt/2 the actual timestep will be equal to or smaller than the timestep parameter, which will be overwritten by the actual timestep

Definition at line 24 of file integ.cpp.

int Chain::IntegrateRK4 ( double  timestep,
int  step 
)

Performs 4-th order Runge-Kutta integration.

Performs 4-th order Runge-Kutta integration.

Parameters:
[in]timestepintegration time step [s]
[in]stepstep in the integration (0/1/2/3)

Definition at line 214 of file integ.cpp.

int Chain::IntegrateRK4Value ( double  timestep,
int  step 
)

Definition at line 126 of file integ.cpp.

int Chain::IntegrateRK4Velocity ( double  timestep,
int  step 
)

Definition at line 170 of file integ.cpp.

int Chain::IntegrateValue ( double  timestep)

Integrate value/velocity only.

Integrate value/velocity only. (for test) See Guendelman et al., SIGGRAPH2003

Definition at line 86 of file integ.cpp.

int Chain::IntegrateVelocity ( double  timestep)

Definition at line 98 of file integ.cpp.

void Chain::InvDyn ( fVec tau)

Inverse dynamics.

Inverse dynamics

Parameters:
[out]taujoint forces/torques

Definition at line 16 of file id.cpp.

int Chain::Load ( const char *  fname,
const char *  charname = 0 
)

Load the chain from a file in original (*.prm) format.

Load the chain from a file in original (*.prm) format.

Parameters:
[in]fnamefile name
[in]charnamecharacter name; each joint is named as "basename:charname"
Returns:
0 if success and -1 otherwise

Definition at line 26 of file load.cpp.

int Chain::LoadXML ( const char *  fname,
const char *  charname = 0 
)

Load the chain from an XML file.

int Chain::NumDOF ( ) [inline]

Total degrees of freedom.

Definition at line 343 of file chain.h.

int Chain::NumJoint ( ) [inline]

Total number of joints.

Definition at line 347 of file chain.h.

int Chain::NumValue ( ) [inline]

Dimension of the joint value vector (using Euler parameter representation for orientation).

Definition at line 351 of file chain.h.

disconnect joint j from its parent

Definition at line 32 of file edit.cpp.

void Chain::reset_scale ( ) [protected]
void Chain::reset_scale_sub ( Joint jnt) [protected]
Joint* Chain::Root ( ) [inline]

Definition at line 151 of file chain.h.

int Chain::Save ( const char *  fname,
const char *  charname = 0 
) const

Save the chain data to a file in original (*.prm) format.

int Chain::Save ( ostream &  ost,
const char *  charname = 0 
) const
int Chain::SaveStatus ( fVec value,
fVec vel,
fVec acc 
)

Save current joint values, velocities, and accelerations.

Definition at line 24 of file chain.cpp.

int Chain::SaveXML ( const char *  fname,
const char *  charname = 0 
) const

Save the chain data to a file in XML format.

int Chain::SaveXML ( ostream &  ost,
const char *  charname = 0 
) const
int Chain::set_abs_position_orientation ( Joint jnt,
const fVec3 abs_pos,
const fMat33 abs_att 
)

Definition at line 396 of file joint.cpp.

void Chain::set_all_torque_given ( Joint cur,
int  _tg 
) [protected]

Definition at line 74 of file vary.cpp.

void Chain::set_relative_positions ( SceneGraph *  sg) [protected]

Definition at line 243 of file edit.cpp.

Change torque/motion control property of all joints.

Definition at line 60 of file vary.cpp.

int Chain::SetCharacterTorqueGiven ( const char *  charname,
int  _tg 
)

Change torque/motion control property of a character.

vary.cpp Create:Katsu Yamane, 04.04.19 functions related to changing joint connectivity

Definition at line 17 of file vary.cpp.

Definition at line 497 of file joint.cpp.

Set all joint forces/torques.

Set all joint forces/torques. The index of the first data of a joint is Joint::i_dof.

Definition at line 746 of file joint.cpp.

Set all joint values.

Set all joint values. The orientation of spherical/free joints are represented as Euler parameters. The index of the first data of a joint is Joint::i_value.

Definition at line 415 of file joint.cpp.

Set all joint velocities/accelerations.

Set all joint velocities/accelerations. The index of the first data of a joint is Joint::i_dof.

Definition at line 456 of file joint.cpp.

int Chain::SetStatus ( const fVec value,
const fVec vel,
const fVec acc 
)

Set current joint values, velocities, and accelerations.

Definition at line 35 of file chain.cpp.

int Chain::SetTorqueGiven ( Joint _joint,
int  _tg 
)

Change torque/motion control property of a joint.

Definition at line 34 of file vary.cpp.

double Chain::TotalCOM ( fVec3 com,
const char *  chname = 0 
)

Center of mass of the chain.

Center of mass of the chain.

Parameters:
[out]comcenter of mass
[in]chnamename of the character to compute com; all joints if omitted
Returns:
the total mass

Definition at line 129 of file fk.cpp.


Friends And Related Function Documentation

friend class Joint [friend]

Definition at line 146 of file chain.h.


Member Data Documentation

double** Chain::all_value [protected]

Pointers to the integration variables.

Pointers to the integration variables.

	 *   all_value += timestep * all_value_dot
	 *   all_vel += timestep * all_vel_dot  

Definition at line 455 of file chain.h.

double** Chain::all_value_dot [protected]

Definition at line 456 of file chain.h.

double** Chain::all_vel [protected]

Definition at line 457 of file chain.h.

double** Chain::all_vel_dot [protected]

Definition at line 458 of file chain.h.

int Chain::do_connect [protected]

true after Connect() was called; application (or subclass) must reset the flag

Definition at line 476 of file chain.h.

true if between BeginCreateChain() and EndCreateChain().

Definition at line 473 of file chain.h.

double* Chain::init_value [protected]

Definition at line 462 of file chain.h.

double* Chain::init_vel [protected]

Definition at line 463 of file chain.h.

double* Chain::j_acc_p[4] [protected]

Definition at line 461 of file chain.h.

double* Chain::j_value_dot[4] [protected]

for 4-th order Runge-Kutta

Definition at line 460 of file chain.h.

int Chain::n_dof [protected]

Definition at line 468 of file chain.h.

int Chain::n_joint [protected]

Definition at line 469 of file chain.h.

int Chain::n_thrust [protected]

total DOF of the joints with t_given = false

Definition at line 470 of file chain.h.

int Chain::n_value [protected]

Definition at line 467 of file chain.h.

Joint* Chain::root [protected]

Chain information.

Definition at line 466 of file chain.h.

std::list<scale_object> Chain::scale_object_list [protected]

Definition at line 517 of file chain.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 Thu Apr 11 2019 03:30:21