The class representing the whole mechanism. May contain multiple characters. More...
#include <chain.h>

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. | |
| Joint * | AddJoint (JointData *joint_data, const char *charname=0) |
Create and add a joint using JointData structure. | |
| Joint * | AddRoot (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. | |
| Joint * | FindCharacterRoot (const char *charname) |
Find the root joint of the character with name charname. | |
| Joint * | FindJoint (const char *jname, const char *charname=0) |
| Find a joint from name. | |
| Joint * | FindJoint (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 ×tep, 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 | |
| Joint * | Root () |
| 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 |
| Joint * | root |
| Chain information. | |
| std::list< scale_object > | scale_object_list |
Friends | |
| class | Joint |
The class representing the whole mechanism. May contain multiple characters.
| Chain::Chain | ( | ) |
| Chain::~Chain | ( | ) | [virtual] |
| void Chain::_apply_scale | ( | Joint * | jnt, |
| double | scale | ||
| ) | [protected] |
| void Chain::add_scale_object | ( | const scale_object & | _s | ) |
| int Chain::AddJoint | ( | Joint * | target, |
| Joint * | p | ||
| ) |
| 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.
| [in] | target | the pointer to the new joint |
| [in] | parent_name | name of the parent joint |
| [in] | charname | character name of the parent joint |
| Joint * Chain::AddJoint | ( | JointData * | joint_data, |
| const char * | charname = 0 |
||
| ) |
| int Chain::AddRoot | ( | Joint * | r | ) |
| void Chain::apply_geom_scale | ( | SceneGraph * | sg, |
| Joint * | cur | ||
| ) | [protected] |
| 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 | ) |
| 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.
| [in] | append | If false (default), clean up the current chain and build from scratch. Otherwise append new joints to the current chain. |
| void Chain::calc_abs_positions | ( | Joint * | cur, |
| SceneGraph * | sg | ||
| ) | [protected] |
| void Chain::calc_rel_positions | ( | Joint * | cur, |
| SceneGraph * | sg | ||
| ) | [protected] |
| void Chain::Clear | ( | ) | [virtual] |
| int Chain::clear_data | ( | ) | [protected, virtual] |
| double Chain::ComJacobian | ( | fMat & | J, |
| fVec3 & | com, | ||
| const char * | chname = 0 |
||
| ) |
Computes the com Jacobian.
Computes the com Jacobian.
| [out] | J | com Jacobian |
| [out] | com | com |
| [in] | chname | name of the character to compute com Jacobian; all joints if omitted |
Definition at line 18 of file jacobi.cpp.
| int Chain::Connect | ( | Joint * | virtual_joint, |
| Joint * | parent_joint | ||
| ) |
| 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.
| [in] | num_char | number of chains to generate |
| [in] | prmname | prm file name |
| [in] | charname | character name (the actual name includes the number starting from init_num) |
| [in] | init_pos | the position offset of the first chain |
| [in] | init_att | the orientation offset of the first chain |
| [in] | pos_offset | the position offset of each chain from the previous |
| [in] | att_offset | the orientation offset of each chain from the previous |
| [in] | init_num | the 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.
| [in] | num_joint | number of joints |
| [in] | joint_data | JointData structure to be used as the template for the joints; each joint will named as joint_data.name + number |
| [in] | charname | character name (optional) |
| [in] | parent_joint | pointer to the root of the serial chain (optional); the global root if omitted or NULL |
| int Chain::Disconnect | ( | Joint * | j | ) |
| int Chain::EndCreateChain | ( | SceneGraph * | sg = NULL | ) |
| Joint * Chain::FindCharacterRoot | ( | const char * | charname | ) |
| 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.
| [in] | jname | joint name |
| [in] | charname | character name |
| Joint * Chain::FindJoint | ( | int | _id | ) |
| int Chain::GetJointAcc | ( | fVec & | accs | ) |
| int Chain::GetJointForce | ( | fVec & | forces | ) |
| int Chain::GetJointList | ( | Joint **& | joints | ) |
| int Chain::GetJointNameList | ( | char **& | jnames | ) |
| int Chain::GetJointValue | ( | fVec & | values | ) |
| int Chain::GetJointVel | ( | fVec & | vels | ) |
| int Chain::init | ( | SceneGraph * | sg | ) | [protected, virtual] |
| void Chain::init_scale | ( | SceneGraph * | sg | ) | [protected] |
| void Chain::init_scale_sub | ( | Node * | node | ) | [protected] |
| int Chain::Integrate | ( | double | timestep | ) |
| 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.
| [in,out] | timestep | inputs maximum timestep and overwritten by the actual timestep |
| [in] | step | step in the integration (0/1) |
| [in] | min_timestep | minimum timestep |
| [in] | max_integ_error | maximum 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
| int Chain::IntegrateRK4 | ( | double | timestep, |
| int | step | ||
| ) |
| int Chain::IntegrateRK4Value | ( | double | timestep, |
| int | step | ||
| ) |
| int Chain::IntegrateRK4Velocity | ( | double | timestep, |
| int | step | ||
| ) |
| int Chain::IntegrateValue | ( | double | timestep | ) |
| int Chain::IntegrateVelocity | ( | double | timestep | ) |
| void Chain::InvDyn | ( | fVec & | tau | ) |
| int Chain::Load | ( | const char * | fname, |
| const char * | charname = 0 |
||
| ) |
| int Chain::LoadXML | ( | const char * | fname, |
| const char * | charname = 0 |
||
| ) |
Load the chain from an XML file.
| int Chain::NumDOF | ( | ) | [inline] |
| int Chain::NumJoint | ( | ) | [inline] |
| int Chain::NumValue | ( | ) | [inline] |
| int Chain::RemoveJoint | ( | Joint * | j | ) |
| void Chain::reset_scale | ( | ) | [protected] |
| void Chain::reset_scale_sub | ( | Joint * | jnt | ) | [protected] |
| Joint* Chain::Root | ( | ) | [inline] |
| 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 | ||
| ) |
| 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 |
| void Chain::set_all_torque_given | ( | Joint * | cur, |
| int | _tg | ||
| ) | [protected] |
| void Chain::set_relative_positions | ( | SceneGraph * | sg | ) | [protected] |
| int Chain::SetAllTorqueGiven | ( | int | _tg | ) |
| int Chain::SetCharacterTorqueGiven | ( | const char * | charname, |
| int | _tg | ||
| ) |
| int Chain::SetJointForce | ( | const fVec & | forces | ) |
Set all joint forces/torques.
Set all joint forces/torques. The index of the first data of a joint is Joint::i_dof.
| int Chain::SetJointValue | ( | const fVec & | values | ) |
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.
| int Chain::SetJointVel | ( | const fVec & | vels | ) |
Set all joint velocities/accelerations.
Set all joint velocities/accelerations. The index of the first data of a joint is Joint::i_dof.
| int Chain::SetTorqueGiven | ( | Joint * | _joint, |
| int | _tg | ||
| ) |
| double Chain::TotalCOM | ( | fVec3 & | com, |
| const char * | chname = 0 |
||
| ) |
double** Chain::all_value [protected] |
double** Chain::all_value_dot [protected] |
double** Chain::all_vel [protected] |
double** Chain::all_vel_dot [protected] |
int Chain::do_connect [protected] |
int Chain::in_create_chain [protected] |
true if between BeginCreateChain() and EndCreateChain().
double* Chain::init_value [protected] |
double* Chain::init_vel [protected] |
double* Chain::j_acc_p[4] [protected] |
double* Chain::j_value_dot[4] [protected] |
int Chain::n_dof [protected] |
int Chain::n_joint [protected] |
int Chain::n_thrust [protected] |
int Chain::n_value [protected] |
Joint* Chain::root [protected] |
std::list<scale_object> Chain::scale_object_list [protected] |