chain.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
3  * All rights reserved. This program is made available under the terms of the
4  * Eclipse Public License v1.0 which accompanies this distribution, and is
5  * available at http://www.eclipse.org/legal/epl-v10.html
6  * Contributors:
7  * The University of Tokyo
8  */
16 #ifndef __CHAIN_H__
17 #define __CHAIN_H__
18 
19 #include <dims_common.h>
20 #include <fMatrix3.h>
21 #include <fEulerPara.h>
22 #ifndef SEGA
23 #include <SceneGraph.h>
24 #endif
25 #include <list>
26 #include <cstring>
27 #include <cstdio>
28 #include "hrpModelExportDef.h"
29 
31 #define DEFAULT_MIN_TIMESTEP 1e-6
32 #define DEFAULT_MAX_INTEG_ERROR 1e-4
33 
35 char* CharName(const char* _name);
36 
38 enum JointType {
39  JUNKNOWN = 0,
45 };
46 
48 enum AxisIndex {
49  AXIS_NULL = -1,
53 };
54 
55 class Joint;
56 
61 struct JointData
62 {
64  name = NULL;
65  parent_name = NULL;
66  j_type = JUNKNOWN;
67  rel_pos.zero();
68  rel_att.identity();
70  mass = 0.0;
71  inertia.zero();
72  com.zero();
73  }
74 
75  JointData(const char* _name, const char* _parent_name, JointType _j_type,
76  const fVec3& _rpos, const fMat33& _ratt, AxisIndex _axis_index,
77  double _mass, const fMat33& _inertia, const fVec3& _com,
78  int _t_given = true) {
79  name = NULL;
80  parent_name = NULL;
81  if(_name)
82  {
83  name = new char [strlen(_name) + 1];
84  strcpy(name, _name);
85  }
86  if(_parent_name)
87  {
88  parent_name = new char [strlen(_parent_name) + 1];
89  strcpy(parent_name, _parent_name);
90  }
91  j_type = _j_type;
92  rel_pos.set(_rpos);
93  rel_att.set(_ratt);
94  axis_index = _axis_index;
95  mass = _mass;
96  inertia.set(_inertia);
97  com.set(_com);
98  t_given = _t_given;
99  }
100  JointData(const JointData& ref) {
101  name = NULL;
102  parent_name = NULL;
103  if(ref.name)
104  {
105  name = new char [strlen(ref.name)];
106  strcpy(name, ref.name);
107  }
108  if(ref.parent_name)
109  {
110  parent_name = new char [strlen(ref.parent_name) + 1];
111  strcpy(parent_name, ref.parent_name);
112  }
113  j_type = ref.j_type;
114  rel_pos.set(ref.rel_pos);
115  rel_att.set(ref.rel_att);
116  axis_index = ref.axis_index;
117  mass = ref.mass;
118  inertia.set(ref.inertia);
119  com.set(ref.com);
120  t_given = ref.t_given;
121  }
122 
124  if(name) delete[] name;
125  if(parent_name) delete[] parent_name;
126  }
127 
128  char* name;
129  char* parent_name;
134  double mass;
137  int t_given;
138 };
139 
145 {
146  friend class Joint;
147 public:
148  Chain();
149  virtual ~Chain();
150 
151  Joint* Root() {
152  return root;
153  }
154 
156 
164  Joint* FindJoint(const char* jname, const char* charname = 0);
165 
167  Joint* FindJoint(int _id);
168 
170  Joint* FindCharacterRoot(const char* charname);
171 
173 
178  int BeginCreateChain(int append = false);
179 
181 
187  Joint* AddRoot(const char* name = 0, const fVec3& grav = fVec3(0.0, 0.0, 9.8));
188 
190 
195  int AddRoot(Joint* r);
196 
198 
204  int Load(const char* fname, const char* charname = 0);
205 
207  int LoadXML(const char* fname, const char* charname = 0);
208 
210 
216  int AddJoint(Joint* target, Joint* p);
218 
225  int AddJoint(Joint* target, const char* parent_name, const char* charname = 0);
226 
228 
234  Joint* AddJoint(JointData* joint_data, const char* charname = 0);
235 
237 
244  int CreateSerial(int num_joint, const JointData& joint_data, const char* charname = 0, Joint* parent_joint = 0);
246 
257  int CreateParallel(int num_char, const char* prmname, const char* charname,
258  const fVec3& init_pos = 0.0, const fMat33& init_att = 1.0,
259  const fVec3& pos_offset = 0.0, const fMat33& att_offset = 1.0,
260  int init_num = 0);
261 
263  int RemoveJoint(Joint* j);
264 
266 
270 #ifdef SEGA
271  int EndCreateChain();
272 #else
273  int EndCreateChain(SceneGraph* sg = NULL);
274 #endif
275 
277 
281  int GetJointNameList(char**& jnames);
282 
284 
288  int GetJointList(Joint**& joints);
289 
291 
296  int SetJointValue(const fVec& values);
297 
299 
303  int SetJointVel(const fVec& vels);
304  int SetJointAcc(const fVec& accs);
305 
307 
311  int SetJointForce(const fVec& forces);
312 
314  int ClearJointForce();
315 
317  int ClearExtForce();
318 
320  int GetJointValue(fVec& values);
321  int GetJointVel(fVec& vels);
322  int GetJointAcc(fVec& accs);
323 
325  int GetJointForce(fVec& forces);
326 
328  void CalcPosition();
329  void CalcVelocity();
330  void CalcAcceleration();
331 
333 
337  void InvDyn(fVec& tau);
338 
340  virtual void Clear();
341 
343  int NumDOF() {
344  return n_dof;
345  }
347  int NumJoint() {
348  return n_joint;
349  }
351  int NumValue() {
352  return n_value;
353  }
354 
356 
362  double TotalCOM(fVec3& com, const char* chname = 0);
363 
365 
372  double ComJacobian(fMat& J, fVec3& com, const char* chname = 0);
373 
375  int Integrate(double timestep);
376 
378 
386  int IntegrateAdaptive(double& timestep, int step, double min_timestep = DEFAULT_MIN_TIMESTEP, double max_integ_error = DEFAULT_MAX_INTEG_ERROR);
387 
389 
394  int IntegrateRK4(double timestep, int step);
395 
397 
401  int IntegrateValue(double timestep);
402  int IntegrateVelocity(double timestep);
403  int IntegrateRK4Value(double timestep, int step);
404  int IntegrateRK4Velocity(double timestep, int step);
405 
407  int Save(const char* fname, const char* charname = 0) const;
408  int Save(ostream& ost, const char* charname = 0) const;
409 
411  int SaveXML(const char* fname, const char* charname = 0) const;
412  int SaveXML(ostream& ost, const char* charname = 0) const;
413 
415  int SaveStatus(fVec& value, fVec& vel, fVec& acc);
416 
418  int SetStatus(const fVec& value, const fVec& vel, const fVec& acc);
419 
421  int Connect(Joint* virtual_joint, Joint* parent_joint);
423  int Disconnect(Joint* j);
424 
426  int SetTorqueGiven(Joint* _joint, int _tg);
428  int SetAllTorqueGiven(int _tg);
430  int SetCharacterTorqueGiven(const char* charname, int _tg);
431 
432  // compute relative position/orientation from absolute values
433  // make sure to call CalcPosition() first to update parent
434  int set_abs_position_orientation(Joint* jnt, const fVec3& abs_pos, const fMat33& abs_att);
435 protected:
437 #ifdef SEGA
438  virtual int init();
439 #else
440  virtual int init(SceneGraph* sg);
441  void set_relative_positions(SceneGraph* sg);
442  void calc_abs_positions(Joint* cur, SceneGraph* sg);
443  void calc_rel_positions(Joint* cur, SceneGraph* sg);
444 #endif
445  virtual int clear_data();
447 
449 
455  double** all_value;
456  double** all_value_dot;
457  double** all_vel;
458  double** all_vel_dot;
460  double* j_value_dot[4];
461  double* j_acc_p[4];
462  double* init_value;
463  double* init_vel;
464 
467  int n_value;
468  int n_dof;
469  int n_joint;
470  int n_thrust;
471 
474 
477 
478  void set_all_torque_given(Joint* cur, int _tg);
479 
480 #ifndef SEGA
481 public:
484  {
485  scale_object(): joint_name("") {
486  scale = 1.0;
487  }
488  scale_object(const scale_object& ref): joint_name(ref.joint_name) {
489  scale = ref.scale;
490  }
492  }
493 
494  void set_joint_name(const char* _joint_name, const char* _char_name) {
495  joint_name = "";
496  if(_joint_name)
497  {
498  joint_name = std::string(_joint_name);
499  if(_char_name)
500  {
501  std::string sep(1, charname_separator);
502  joint_name.append(sep);
503  joint_name.append(std::string(_char_name));
504  }
505  }
506  }
507 
508  double scale;
509  std::string joint_name;
510  };
511 
512  void add_scale_object(const scale_object& _s);
513  void clear_scale_object_list();
514 
515  void ApplyGeomScale(SceneGraph* sg);
516 protected:
517  std::list<scale_object> scale_object_list;
518 
519  void init_scale(SceneGraph* sg);
520  virtual void apply_scale();
521  void apply_scale(const scale_object& _s);
522  void reset_scale();
523  void init_scale_sub(Node* node);
524 
525  void apply_scale_top(Joint* top, double scale);
526  void apply_scale_sub(Joint* cur, double scale);
527  void reset_scale_sub(Joint* jnt);
528 
529  void _apply_scale(Joint* jnt, double scale);
530  void apply_geom_scale(SceneGraph* sg, Joint* cur);
531 #endif
532 };
533 
539 {
540  friend class Chain;
541 public:
542  Joint();
543  Joint(const char* name, JointType jt = JUNKNOWN,
544  const fVec3& rpos = 0.0, const fMat33& ratt = 1.0,
545  AxisIndex _axis_index = AXIS_NULL,
546  int t_given = true);
547  Joint(JointData* jdata, const char* charname);
548  ~Joint();
549 
550  void SetJointData(JointData* jdata, const char* charname);
551  void UpdateJointType();
552 
558  int SetJointValue(double _q);
559  int SetJointVel(double _qd);
560  int SetJointAcc(double _qdd);
561  int GetJointValue(double& _q);
562  int GetJointVel(double& _qd);
563  int GetJointAcc(double& _qdd);
564  int SetJointForce(double _tau);
565  int GetJointForce(double& _tau);
573  int SetJointValue(const fMat33& r);
574  int SetJointValue(const fEulerPara& ep);
575  int SetJointVel(const fVec3& rd);
576  int SetJointAcc(const fVec3& rdd);
577  int SetJointAcc(double ax, double ay, double az);
578  int GetJointValue(fMat33& r);
579  int GetJointVel(fVec3& rd);
580  int GetJointAcc(fVec3& rdd);
581  int SetJointForce(const fVec3& _n3);
582  int GetJointForce(fVec3& _n3);
590  int SetJointValue(const fVec3& p, const fMat33& r);
591  int SetJointValue(const fVec3& p, const fEulerPara& ep);
592  int SetJointVel(const fVec3& pd, const fVec3& rd);
593  int SetJointAcc(const fVec3& pdd, const fVec3& rdd);
594  int SetJointAcc(double lx, double ly, double lz, double ax, double ay, double az);
595  int GetJointValue(fVec3& p, fMat33& r);
596  int GetJointVel(fVec3& pd, fVec3& rd);
597  int GetJointAcc(fVec3& pdd, fVec3& rdd);
598  int SetJointForce(const fVec3& _f3, const fVec3& _n3);
599  int GetJointForce(fVec3& _f3, fVec3& _n3);
602  int SetJointPosition(const fVec3& p);
605  int SetJointOrientation(const fMat33& r);
606 
608  void SetRotateJointType(const fVec3& rpos, const fMat33& ratt, AxisIndex ai);
610  void SetSlideJointType(const fVec3& rpos, const fMat33& ratt, AxisIndex ai);
612  void SetSphereJointType(const fVec3& rpos, const fMat33& ratt);
614  void SetFixedJointType(const fVec3& rpos, const fMat33& ratt);
616  void SetFreeJointType(const fVec3& rpos, const fMat33& ratt);
617 
619  int CalcJacobian(fMat& J);
620 
622  int CalcJacobian2(fMat* J2);
623 
625  int CalcJdot(fVec& jdot);
626 
628  int DescendantDOF();
629 
631  int DescendantNumJoints();
632 
634  int isDescendant(Joint* target);
635 
637  int isAscendant(Joint* target);
638 
640  double TotalMass();
641 
643  double Scale() {
644  return cur_scale;
645  }
646 
648  char* CharName() const {
649  char* ret = strrchr(name, charname_separator);
650  if(ret) return ret+1;
651  return 0;
652  }
653 
655  void SetName(const char* _name, const char* _charname = 0) {
656  if(name) delete[] name;
657  name = 0;
658  if(basename) delete[] basename;
659  basename = 0;
660  if(_name)
661  {
662  if(_charname)
663  {
664  name = new char [strlen(_name) + strlen(_charname) + 2];
665  sprintf(name, "%s%c%s", _name, charname_separator, _charname);
666  }
667  else
668  {
669  name = new char [strlen(_name) + 1];
670  strcpy(name, _name);
671  }
672  char* ch = strrchr(name, charname_separator);
673  if(ch) *ch = '\0';
674  basename = new char [strlen(name) + 1];
675  strcpy(basename, name);
676  if(ch) *ch = charname_separator;
677  }
678  }
679 
686 
690 
691  char* name;
692  char* basename;
693  char* realname;
695 
699 
703 
704  double mass;
707  double gear_ratio;
709  int t_given;
710 
715  int n_dof;
716  int n_thrust;
718 
719  int i_value;
720  int i_dof;
721  int i_thrust;
722  int i_joint;
723 
724  double q;
725  double qd;
726  double qdd;
727 
732 
733  double tau;
738 
749 
755  fVec3 joint_f, total_f;
756  fVec3 joint_n, total_n;
768 protected:
770 
771  double total_mass();
772 
773  void init();
774  void init_arrays();
775  void init_virtual();
776  void _init_virtual();
777 
778  void clear_data();
779 
780  int pre_integrate();
781  int post_integrate();
782 
783  void clear();
784 
785  int set_joint_value(const fVec& values);
786  int set_joint_vel(const fVec& vels);
787  int set_joint_acc(const fVec& accs);
788  int set_joint_force(const fVec& forces);
789 
790  int get_joint_value(fVec& values);
791  int get_joint_vel(fVec& vels);
792  int get_joint_acc(fVec& accs);
793  int get_joint_force(fVec& forces);
794 
795  void calc_position();
796  void calc_velocity();
797  void calc_acceleration();
798 
799  void inv_dyn();
800  void inv_dyn_1();
801  void inv_dyn_2();
802  void calc_joint_force(fVec& tau);
803 
804  void get_joint_name_list(char** jnames);
805  void get_joint_list(Joint** joints);
806 
807  void add_child(Joint* j);
808  int remove_child(Joint* j);
809  Joint* find_joint(const char* n, const char* charname);
810  Joint* find_joint(int _id);
811 
812  int calc_jacobian(fMat& J, Joint* target);
813  int calc_jacobian_rotate(fMat& J, Joint* target);
814  int calc_jacobian_slide(fMat& J, Joint* target);
815  int calc_jacobian_sphere(fMat& J, Joint* target);
816  int calc_jacobian_free(fMat& J, Joint* target);
817 
818  int calc_jacobian_2(fMat* J, Joint* target);
819  int calc_jacobian_2_rotate_sub(fMat* J, Joint* target, Joint* j1);
820  int calc_jacobian_2_slide_sub(fMat* J, Joint* target, Joint* j1);
821  int calc_jacobian_2_sphere_sub(fMat* J, Joint* target, Joint* j1);
822  int calc_jacobian_2_free_sub(fMat* J, Joint* target, Joint* j1);
823 
824  int calc_jacobian_2_rotate_rotate(fMat* J, Joint* target, Joint* j1, const fVec3& axis1, int index1, const fVec3& axis2, int index2);
825  int calc_jacobian_2_slide_rotate(fMat* J, Joint* target, Joint* jk, const fVec3& k_axis, int k_index, const fVec3& loc_axis, int loc_index);
826  int calc_jacobian_2_rotate_slide(fMat* J, Joint* target, Joint* jk, const fVec3& k_axis, int k_index, const fVec3& loc_axis, int loc_index);
827 
828 
829  int descendant_dof();
830  int descendant_num_joints();
831  int is_descendant(Joint* cur, Joint* target);
832 
833  int save(ostream& ost, int indent, const char* charname) const;
834  int save_xml(ostream& ost, int indent, const char* charname) const;
835 
836  int clear_joint_force();
837  int clear_ext_force();
838 
839  double total_com(fVec3& com, const char* chname);
840  double com_jacobian(fMat& J, fVec3& com, const char* chname);
841 
842 private:
843  double cur_scale;
844 };
845 
846 #endif
std::list< scale_object > scale_object_list
Definition: chain.h:517
char * realname
name of the real joint (for closed chains)
Definition: chain.h:693
fVec3 loc_lin_vel
linear velocity in local frame
Definition: chain.h:743
scale_object(const scale_object &ref)
Definition: chain.h:488
3x3 matrix class.
Definition: fMatrix3.h:29
double mass
mass
Definition: chain.h:704
virtual int init(SceneGraph *sg)
Initialize the parameters.
Definition: init.cpp:22
fVec3 axis
joint axis in local frame (for 1DOF joints)
Definition: chain.h:696
Joint * child
pointer to the child joint
Definition: chain.h:685
#define HRPBASE_EXPORT
#define DEFAULT_MIN_TIMESTEP
Defines for IntegAdaptiveEuler.
Definition: chain.h:31
fVec3 loc_com_acc
com acceleration in local frame
Definition: chain.h:748
int SetJointValue(const fVec &values)
Set all joint values.
Definition: joint.cpp:415
int n_dof
degrees of freedom (0/1/3/6)
Definition: chain.h:715
Definition: chain.h:39
void clear(CorbaSequence &seq)
JointType j_type
joint type
Definition: chain.h:130
void clear_data()
Definition: vary.cpp:160
void SetName(const char *_name, const char *_charname=0)
Change the joint name.
Definition: chain.h:655
double rotor_inertia
Definition: chain.h:708
void zero()
Creates a zero vector.
Definition: fMatrix3.h:283
int t_given
torque or motion controlled
Definition: chain.h:709
void set(const fMat33 &mat)
Copies a matrix.
Definition: fMatrix3.cpp:623
int n_thrust
DOF for motion controlled joints.
Definition: chain.h:716
void zero()
Definition: fMatrix3.cpp:236
int in_create_chain
true if between BeginCreateChain() and EndCreateChain().
Definition: chain.h:473
#define DEFAULT_MAX_INTEG_ERROR
Definition: chain.h:32
fVec3 rpos_real
relative position in the real joint frame
Definition: chain.h:688
friend class Chain
Definition: chain.h:540
double * init_value
Definition: chain.h:462
Definition: chain.h:51
~JointData()
Definition: chain.h:123
fMat33 rel_att
initial orientation in parent joint&#39;s frame
Definition: chain.h:132
png_voidp int value
Definition: png.h:2113
fVec3 loc_ang_vel
angular velocity in local frame
Definition: chain.h:744
fVec3 loc_lin_acc
linear acceleration in local frame
Definition: chain.h:746
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
fVec3 init_pos
origin of the joint value (for prismatic joints)
Definition: chain.h:697
Definition: chain.h:52
Joint * root
Chain information.
Definition: chain.h:466
char * parent_name
parent joint&#39;s name
Definition: chain.h:129
int SetJointAcc(const fVec &accs)
Definition: joint.cpp:497
Euler parameter representation of orientation.
fVec3 com
link center of mass in local frame
Definition: chain.h:136
void identity()
Identity matrix.
Definition: fMatrix3.cpp:230
double mass
link mass
Definition: chain.h:134
int n_joint
Definition: chain.h:469
fVec3 p_ang_acc
Definition: chain.h:765
void set(double *v)
Set element values from array or three values.
Definition: fMatrix3.h:314
double cur_scale
Definition: chain.h:843
fVec3 loc_com_vel
com velocity in local frame
Definition: chain.h:745
static char charname_separator
Definition: dims_common.h:19
int GetJointVel(fVec &vels)
Definition: joint.cpp:172
Definition: chain.h:50
int SetJointVel(const fVec &vels)
Set all joint velocities/accelerations.
Definition: joint.cpp:456
fEulerPara rel_ep
Euler parameter representation of rel_att (for 0/3/6 DOF joints)
Definition: chain.h:702
char * basename
joint base name (without the character name)
Definition: chain.h:692
int n_thrust
total DOF of the joints with t_given = false
Definition: chain.h:470
void init()
Definition: init.cpp:135
JointData()
Definition: chain.h:63
int SetJointAcc(double _qdd)
Definition: joint.cpp:580
double q
joint value (for 1DOF joints)
Definition: chain.h:724
double tau
joint force/torque (for 1DOF joints)
Definition: chain.h:733
fVec3 p_ang_vel
Definition: chain.h:763
int GetJointAcc(fVec &accs)
Definition: joint.cpp:214
spherical (3DOF)
Definition: chain.h:43
std::string basename(const std::string name)
Euler parameter class.
Definition: fEulerPara.h:28
int i_thrust
index in all motion controlled joints
Definition: chain.h:721
int NumValue()
Dimension of the joint value vector (using Euler parameter representation for orientation).
Definition: chain.h:351
fVec3 rel_pos
(initial) position in parent joint&#39;s frame (for 0/3/6 DOF joints)
Definition: chain.h:700
fVec3 rel_ang_acc
Definition: chain.h:731
int GetJointValue(double &_q)
Definition: joint.cpp:256
int n_root_dof
total DOF in the root side
Definition: chain.h:717
int i_dof
index in all DOF
Definition: chain.h:720
int SetJointForce(double _tau)
Definition: joint.cpp:783
double Scale()
Returns the scale applied to the joint.
Definition: chain.h:643
double ** all_value
Pointers to the integration variables.
Definition: chain.h:455
int n_dof
Definition: chain.h:468
double qd
joint velocity (for 1DOF joints)
Definition: chain.h:725
double ** all_vel_dot
Definition: chain.h:458
fVec3 tau_n
joint torque for 3 and 6 DOF joints
Definition: chain.h:735
def j(str, encoding="cp932")
JointType j_type
joint type
Definition: chain.h:694
int NumDOF()
Total degrees of freedom.
Definition: chain.h:343
fVec3 total_f
Definition: chain.h:755
fVec3 p_lin_vel
Definition: chain.h:761
fVec3 rel_ang_vel
Definition: chain.h:729
fVec3 total_n
Definition: chain.h:756
fVec3 ext_force
external force
Definition: chain.h:736
fMat33 abs_att
absolute orientation
Definition: chain.h:742
char * CharName() const
Returns the character name.
Definition: chain.h:648
Chain * chain
Definition: chain.h:769
char * name
joint name
Definition: chain.h:128
int do_connect
true after Connect() was called; application (or subclass) must reset the flag
Definition: chain.h:476
char * name
joint name (including the character name)
Definition: chain.h:691
char * CharName(const char *_name)
Extracts the character name from a joint name.
Definition: chain.cpp:17
int n_value
Definition: chain.h:467
Joint * Root()
Definition: chain.h:151
fMat33 inertia
link inertia
Definition: chain.h:135
fVec3 tau_f
joint force for 6DOF joints
Definition: chain.h:734
fMat33 init_att
origin of the joint value (for rotational joints)
Definition: chain.h:698
XML utility functions.
Definition: chain.h:483
Vector of generic size.
Definition: fMatrix.h:491
Joint * brother
pointer to the brother joint
Definition: chain.h:684
void append(SDOPackage::NVList &dest, const SDOPackage::NVList &src)
double * init_vel
Definition: chain.h:463
fVec3 loc_com
center of mass in local frame
Definition: chain.h:706
JointData(const char *_name, const char *_parent_name, JointType _j_type, const fVec3 &_rpos, const fMat33 &_ratt, AxisIndex _axis_index, double _mass, const fMat33 &_inertia, const fVec3 &_com, int _t_given=true)
Definition: chain.h:75
3x3 matrix and 3-element vector classes.
fixed (0DOF)
Definition: chain.h:40
int GetJointForce(fVec &forces)
Obtain the joint forces/torques.
Definition: joint.cpp:866
double ** all_value_dot
Definition: chain.h:456
fMat33 ratt_real
relative orientation in the real joint frame
Definition: chain.h:689
prismatic (1DOF)
Definition: chain.h:42
fMat33 rel_att
(initial) orientation in parent joint&#39;s frame (for 0/3/6 DOF joints)
Definition: chain.h:701
fVec3 rel_lin_vel
Definition: chain.h:728
double ** all_vel
Definition: chain.h:457
int GetJointAcc(double &_qdd)
Definition: joint.cpp:282
The class representing the whole mechanism. May contain multiple characters.
Definition: chain.h:144
int SetJointForce(const fVec &forces)
Set all joint forces/torques.
Definition: joint.cpp:746
std::string sprintf(char const *__restrict fmt,...)
Temporary storage for basic joint information.
Definition: chain.h:61
int SetJointValue(double _q)
Definition: joint.cpp:538
int GetJointForce(double &_tau)
Definition: joint.cpp:796
int GetJointValue(fVec &values)
Obtain the joint values/velocities/accelerations.
Definition: joint.cpp:124
friend class Joint
Definition: chain.h:146
virtual int clear_data()
Clear arrays only; don&#39;t delete joints.
Definition: vary.cpp:127
void set_joint_name(const char *_joint_name, const char *_char_name)
Definition: chain.h:494
int NumJoint()
Total number of joints.
Definition: chain.h:347
double qdd
joint acceleration (for 1DOF joints)
Definition: chain.h:726
JointType
Enums for joint types.
Definition: chain.h:38
AxisIndex
Direction of a 1-DOF joint.
Definition: chain.h:48
3-element vector class.
Definition: fMatrix3.h:206
double gear_ratio
Definition: chain.h:707
fVec3 ext_moment
external moment around the local frame
Definition: chain.h:737
rotational (1DOF)
Definition: chain.h:41
fVec3 abs_pos
absolute position
Definition: chain.h:741
The class for representing a joint.
Definition: chain.h:538
Joint * real
pointer to the real (connected) joint; for closed chains.
Definition: chain.h:687
int i_joint
index of the joint
Definition: chain.h:722
fVec3 p_lin_acc
Definition: chain.h:764
fMat33 inertia
intertia
Definition: chain.h:705
fVec3 rel_lin_acc
Definition: chain.h:730
fVec3 rel_pos
initial position in parent joint&#39;s frame
Definition: chain.h:131
int GetJointVel(double &_qd)
Definition: joint.cpp:269
int SetJointVel(double _qd)
Definition: joint.cpp:562
Joint * parent
pointer to the parent joint
Definition: chain.h:683
fVec3 loc_ang_acc
angular acceleration in local frame
Definition: chain.h:747
free (6DOF)
Definition: chain.h:44
int i_value
index in all joint values
Definition: chain.h:719
JointData(const JointData &ref)
Definition: chain.h:100
int t_given
if true, the joint is torque controlled, otherwise position controlled (high-gain control) ...
Definition: chain.h:137
fEulerPara p_ep_dot
Definition: chain.h:762
Matrix of generic size. The elements are stored in a one-dimensional array in row-major order...
Definition: fMatrix.h:46
AxisIndex axis_index
direction of the joint axis (only for 1DOF joints)
Definition: chain.h:133
std::string joint_name
Definition: chain.h:509


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:37