ik.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 __IK_H__
17 #define __IK_H__
18 
19 #include <chain.h>
20 
21 class IKConstraint;
22 class IKHandle;
23 
24 //#define MEASURE_TIME
25 
26 //#define MAX_CONSTRAINT 128
27 #define MIN_JOINT_WEIGHT 0.01
28 
29 #define MAX_CONDITION_NUMBER 100.0
30 
31 static const char joint_name_separator = '_';
32 
37 class IK
38  : virtual public Chain
39 {
40  friend class IKConstraint;
41  friend class IKHandle;
42  friend class IKDesire;
43 public:
47  enum ConstType {
53  };
57  enum Priority {
62  };
66  enum ConstIndex {
69  };
70 
72  IK();
74  ~IK();
75 
78  return n_constraints;
79  }
82 
84  int LoadMarkerXML(const char* fname, const char* _charname);
85 
91  int AddConstraint(IKConstraint* _constraint);
97  int RemoveConstraint(int _id);
101  int RemoveAllConstraints();
102 
108  double Update(double timestep);
109 
111  double Update(double max_timestep, double min_timestep, double max_integ_error = DEFAULT_MAX_INTEG_ERROR);
112 
120  IKConstraint* FindConstraint(ConstType _type, const char* jname, const char* charname = 0);
121 
126  IKConstraint* FindConstraint(int _id);
127 
132  int ConstraintIndex(ConstType _type, const char* jname);
137  int ConstraintIndex(int _id);
138 
143  int ConstraintID(ConstType _type, const char* jname);
148  int ConstraintID(int _index);
149 
151  int ResetAllConstraints();
152 
155 
157  int SetJointWeight(const char* jname, double _weight);
159  int SetJointWeight(const char* jname, const fVec& _weight);
160 
162  int EnableDesire(const char* jname);
164  int DisableDesire(const char* jname);
166  int SetDesireGain(const char* jname, double _gain);
167 
169  void SetMaxConditionNumber(double cn) {
170  max_condnum = cn;
171  }
174  return max_condnum;
175  }
176 
178  void SetConstraintScale(double _scale, const char* charname = 0);
180  void SetCharacterScale(double _scale, const char* charname = 0);
181 
183 
190  IKHandle* AddMarker(const std::string& label, const std::string& linkname, const std::string& charname, const fVec3& rel_pos);
191 #ifndef SEGA
192  IKHandle* AddMarker(const char* marker_name, Joint* parent_joint, const fVec3& abs_pos = 0.0);
193  int SaveMarkers(const char* fname);
194  int EditMarker(IKHandle* marker, const char* body_name, Joint* parent_joint, const fVec3& abs_pos = 0.0);
195 #endif
196 protected:
197 #ifdef SEGA
198  int init();
199  int myinit();
200 #else
201  int init(SceneGraph* sg);
202  int myinit(SceneGraph* sg);
203  int load_markers(SceneGraph* sg, Joint* rj);
204  int load_markers(TransformNode* marker_top);
205  IKHandle* add_marker(const char* marker_name, Joint* parent_joint, const fVec3& abs_pos);
206  IKHandle* add_marker(TransformNode* tn);
207  int edit_marker(IKHandle* marker, const char* body_name, Joint* parent_joint, const fVec3& abs_pos);
208  int save_marker(TransformNode* top_tnode, IKHandle* h);
209 #endif
210 
212  int calc_jacobian();
213 
214  int calc_feedback();
215 
217  double solve_ik();
218 
219  int copy_jacobian();
220 
221  void set_character_scale(Joint* jnt, double _scale, const char* charname);
222 
225 
228 
231 
233  int assign_constraints(int _n);
234 
240 
242  double max_condnum;
243 
246 
247 };
248 
254 {
255  friend class IK;
256 public:
258 
266  IKConstraint(IK* _ik, const char* _jname, Joint* _jnt, IK::Priority _pri, double _gain) {
267  ik = _ik;
268  joint_name = 0;
269  enabled = true;
270  active = true;
271  if(_jname)
272  {
273  joint_name = new char [strlen(_jname) + 1];
274  strcpy(joint_name, _jname);
275  }
276  joint = _jnt;
277  n_const = 0;
278  priority = _pri;
279  gain = _gain;
280  i_const = -1;
281  id = -1;
282  is_dropped = false;
283  }
284 
286  virtual ~IKConstraint() {
287  if(joint_name) delete[] joint_name;
288  }
289 
291  virtual IK::ConstType GetType() = 0;
292 
293  virtual int Reset() {
294  return 0;
295  }
296 
298  void Enable() {
299  enabled = true;
300  }
302  void Disable() {
303  enabled = false;
304  }
305 
307  void Activate() {
308  active = true;
309  }
311  void Diactivate() {
312  active = false;
313  }
315  int Active() {
316  return active;
317  }
318 
320  void SetGain(double _gain) {
321  gain = _gain;
322  }
324  double GetGain() {
325  return gain;
326  }
327 
330  priority = _pri;
331  }
334  return priority;
335  }
336 
337  int iConst() {
338  return i_const;
339  }
340  int nConst() {
341  return n_const;
342  }
343 
345  return joint;
346  }
347  int ID() {
348  return id;
349  }
350  int Dropped() {
351  if(priority == IK::HIGH_IF_POSSIBLE) return is_dropped;
352  return false;
353  }
354 
355  virtual void SetCharacterScale(double _scale, const char* charname = 0) {
356  }
357 
358 protected:
360 
368  virtual int calc_jacobian();
369  virtual int calc_jacobian_rotate(Joint* cur) {
370  return 0;
371  }
372  virtual int calc_jacobian_slide(Joint* cur) {
373  return 0;
374  }
375  virtual int calc_jacobian_sphere(Joint* cur) {
376  return 0;
377  }
378  virtual int calc_jacobian_free(Joint* cur) {
379  return 0;
380  }
381 
383  int calc_jacobian(Joint* cur);
385  int copy_jacobian();
386 
388  virtual int calc_feedback() = 0;
389 
390  IK* ik;
392  char* joint_name;
393  int id;
394 
396  double gain;
398  int n_const;
399  int enabled;
400  int active;
401 
402  fMat J;
404  int i_const;
405 
407 
408 private:
409  int count_constraints();
410 };
411 
416 class IKHandle
417  : public IKConstraint
418 {
419  friend class IK;
420 public:
433  IKHandle(IK* _ik, const char* _jname, Joint* _jnt,
434  IK::ConstIndex cindex[6], IK::Priority _pri, double _gain,
435  const fVec3& _rel_pos = 0.0, const fMat33& _rel_att = 1.0,
436  Joint* _other_joint = 0)
437  : IKConstraint(_ik, _jname, _jnt, _pri, _gain),
438  rel_pos(_rel_pos), rel_att(_rel_att) {
439  for(int i=0; i<6; i++)
440  {
441  const_index[i] = cindex[i];
442  if(const_index[i] == IK::HAVE_CONSTRAINT)
443  n_const++;
444  }
445  other_joint = _other_joint;
446  // compute the current absolute position/orientation
447  abs_pos.zero();
448  abs_att.identity();
449  if(joint)
450  {
451  abs_att.mul(joint->abs_att, rel_att);
452  abs_pos.mul(joint->abs_att, rel_pos);
453  abs_pos += joint->abs_pos;
454  // relative position/orientation
455  if(other_joint)
456  {
457  static fVec3 pp;
458  static fMat33 rt, att;
459  rt.tran(other_joint->abs_att);
460  att.set(abs_att);
461  pp.sub(abs_pos, other_joint->abs_pos);
462  abs_pos.mul(rt, pp);
463  abs_att.mul(rt, att);
464  }
465  }
466  J.resize(n_const, ik->NumDOF());
467  J.zero();
468  fb.resize(n_const);
469  fb.zero();
471  weight = 1.0;
472  }
473 
475  }
476 
478  int Reset() {
479  if(joint)
480  {
481  abs_att.mul(joint->abs_att, rel_att);
482  abs_pos.mul(joint->abs_att, rel_pos);
483  abs_pos += joint->abs_pos;
484  // relative position/orientation
485  if(other_joint)
486  {
487  static fVec3 pp;
488  static fMat33 rt, att;
489  rt.tran(other_joint->abs_att);
490  att.set(abs_att);
491  pp.sub(abs_pos, other_joint->abs_pos);
492  abs_pos.mul(rt, pp);
493  abs_att.mul(rt, att);
494  }
495  }
496  return 0;
497  }
499  void SetPos(const fVec3& _abs_pos) {
500  abs_pos.set(_abs_pos);
501  }
503  void SetAtt(const fMat33& _abs_att) {
504  abs_att.set(_abs_att);
505  }
506 
508  void GetPos(fVec3& _abs_pos) {
509  _abs_pos.set(abs_pos);
510  }
512  void GetAtt(fMat33& _abs_att) {
513  _abs_att.set(abs_att);
514  }
515 
517  void SetRelPos(const fVec3& _rel_pos) {
518  rel_pos.set(_rel_pos);
519  Reset();
520  }
521 
523  return IK::HANDLE_CONSTRAINT;
524  }
525 
526  void GetConstIndex(IK::ConstIndex _cindex[]) {
527  for(int i=0; i<6; i++)
528  {
529  _cindex[i] = const_index[i];
530  }
531  }
532 
533  void SetCharacterScale(double _scale, const char* charname = 0);
534 
535 protected:
536  int calc_jacobian();
537 
538  int calc_feedback();
539 
542 
543  IK::ConstIndex const_index[6];
546 
549 };
550 
555 class IKDesire
556  : public IKConstraint
557 {
558  friend class IK;
559 public:
560  IKDesire(IK* _ik, const char* _jname, Joint* _jnt,
561  IK::Priority _pri, double _gain)
562  : IKConstraint(_ik, _jname, _jnt, _pri, _gain) {
563  q_des = 0.0;
564  att_des.identity();
565  pos_des.zero();
566  if(joint && joint->n_dof > 0)
567  {
568  n_const = joint->n_dof;
569  J.resize(joint->n_dof, ik->NumDOF());
570  J.zero();
571  fb.resize(joint->n_dof);
572  fb.zero();
574  weight = 1.0;
575  switch(joint->j_type)
576  {
577  case JROTATE:
578  case JSLIDE:
579  joint->GetJointValue(q_des);
580  break;
581  case JSPHERE:
582  joint->GetJointValue(att_des);
583  break;
584  case JFREE:
585  joint->GetJointValue(pos_des, att_des);
586  break;
587  default:
588  break;
589  }
590  }
591  }
592 
594  }
595 
596  int Reset() {
597  if(joint && joint->n_dof > 0)
598  {
599  switch(joint->j_type)
600  {
601  case JROTATE:
602  case JSLIDE:
603  joint->GetJointValue(q_des);
604  break;
605  case JSPHERE:
606  joint->GetJointValue(att_des);
607  break;
608  case JFREE:
609  joint->GetJointValue(pos_des, att_des);
610  break;
611  default:
612  break;
613  }
614  }
615  return 0;
616  }
617 
619  return IK::DESIRE_CONSTRAINT;
620  }
621 
622  void SetDesire(double _q) {
623  q_des = _q;
624  }
625  void SetDesire(const fMat33& _att) {
626  att_des.set(_att);
627  }
628  void SetDesire(const fVec3& _pos, const fMat33& _att) {
629  pos_des.set(_pos);
630  att_des.set(_att);
631  }
632  void SetDesire(const fVec3& _pos) {
633  pos_des.set(_pos);
634  }
635 
636  void SetCharacterScale(double _scale, const char* charname = 0);
637 protected:
638  int calc_jacobian_rotate(Joint* cur);
639  int calc_jacobian_slide(Joint* cur);
640  int calc_jacobian_sphere(Joint* cur);
641  int calc_jacobian_free(Joint* cur);
642 
643  int calc_feedback();
644 
645  double q_des;
648 };
649 
654 class IKCom
655  : public IKConstraint
656 {
657 public:
658  IKCom(IK* _ik, const char* _charname, IK::ConstIndex cindex[3],
659  IK::Priority _pri, double _gain)
660  : IKConstraint(_ik, 0, 0, _pri, _gain) {
661  charname = 0;
662  if(_charname)
663  {
664  charname = new char [strlen(_charname)+1];
665  strcpy(charname, _charname);
666  }
667  n_const = 0;
668  for(int i=0; i<3; i++)
669  {
670  const_index[i] = cindex[i];
671  if(const_index[i] == IK::HAVE_CONSTRAINT)
672  n_const++;
673  }
674  fb.resize(n_const);
675  des_com.zero();
676  cur_com.zero();
677  if(_ik)
678  {
679  _ik->CalcPosition();
680  _ik->TotalCOM(cur_com, _charname);
681  des_com.set(cur_com);
682  }
683  }
684  ~IKCom() {
685  if(charname) delete[] charname;
686  }
687 
689  return IK::COM_CONSTRAINT;
690  }
691  int Reset() {
692  ik->TotalCOM(des_com, charname);
693  return 0;
694  }
695  void SetPos(const fVec3& p) {
696  des_com.set(p);
697  }
698 
699 protected:
700  int calc_jacobian();
701  int calc_feedback();
702 
703  IK::ConstIndex const_index[3];
704  char* charname;
707 };
708 
714  : public IKConstraint
715 {
716  friend class IK;
717 public:
718  IKScalarJointLimit(IK* _ik, const char* _jname, Joint* _jnt,
719  IK::Priority _pri, double _gain)
720  : IKConstraint(_ik, _jname, _jnt, _pri, _gain) {
721  min_limit = false;
722  max_limit = false;
723  q_min = 0.0;
724  q_max = 0.0;
725  if(joint && (joint->j_type == JROTATE || joint->j_type == JSLIDE))
726  {
727  n_const = 1;
728  J.resize(1, ik->NumDOF());
729  J.zero();
730  fb.resize(1);
731  fb.zero();
732  weight.resize(1);
733  weight = 1.0;
734  }
735  else
736  {
737  enabled = false;
738  }
739  }
740 
742  }
743 
746  }
747 
748  void SetMax(double _q_max) {
749  q_max = _q_max;
750  max_limit = true;
751  }
752  void SetMin(double _q_min) {
753  q_min = _q_min;
754  min_limit = true;
755  }
756  double GetMax() {
757  return q_max;
758  }
759  double GetMin() {
760  return q_min;
761  }
762 
763  void SetCharacterScale(double _scale, const char* charname = 0);
764 protected:
765  int calc_jacobian_rotate(Joint* cur);
766  int calc_jacobian_slide(Joint* cur);
767 
768  int calc_feedback();
769 
770  int min_limit, max_limit;
771  double q_min, q_max;
772 };
773 
774 #endif
int ConstraintIndex(ConstType _type, const char *jname)
Definition: ik.cpp:511
int n_const[N_PRIORITY_TYPES]
number of constraints of each type
Definition: ik.h:238
int SetDesireGain(const char *jname, double _gain)
Set gain of desire constraint of the specific joint.
Definition: ik.cpp:578
int n_constraints
number of current constraints
Definition: ik.h:224
Base class for constraints.
Definition: ik.h:253
fVec3 rel_pos
Definition: ik.h:544
3x3 matrix class.
Definition: fMatrix3.h:29
double TotalCOM(fVec3 &com, const char *chname=0)
Center of mass of the chain.
Definition: fk.cpp:129
IK()
Default constructor.
Definition: ik.cpp:17
int SetJointWeight(const char *jname, double _weight)
Set joint weight, for single-DOF joints.
Definition: ik.cpp:551
void Enable()
enable the constraint
Definition: ik.h:298
void SetGain(double _gain)
set the gain
Definition: ik.h:320
virtual int calc_jacobian_sphere(Joint *cur)
Definition: ik.h:375
char * charname
target character name
Definition: ik.h:704
double GetMaxConditionNumber()
Get maximum condition number.
Definition: ik.h:173
double solve_ik()
compute the joint velocity
Definition: update_ik.cpp:157
int edit_marker(IKHandle *marker, const char *body_name, Joint *parent_joint, const fVec3 &abs_pos)
Definition: ik.cpp:306
int resize(int i, int j)
Changes the matrix size.
Definition: fMatrix.h:133
int min_limit
Definition: ik.h:770
fMat33 abs_att
current constraint orientation
Definition: ik.h:541
IKHandle * AddMarker(const std::string &label, const std::string &linkname, const std::string &charname, const fVec3 &rel_pos)
Add new marker constraint.
Definition: ik.cpp:244
int init(SceneGraph *sg)
Initialize the parameters.
Definition: ik.cpp:54
Priority
Definition: ik.h:57
fVec3 des_com
desired COM position
Definition: ik.h:705
void set(const fMat33 &mat)
Copies a matrix.
Definition: fMatrix3.cpp:623
int ResetAllConstraints()
Reset all constraints.
Definition: ik.cpp:532
int RemoveAllConstraints()
Definition: ik.cpp:454
center of mass position
Definition: ik.h:50
friend fMat33 tran(const fMat33 &m)
Returns the transpose.
Definition: fMatrix3.cpp:607
Position constraint.
Definition: ik.h:416
void SetRelPos(const fVec3 &_rel_pos)
set relative position of the constraint
Definition: ik.h:517
IKConstraint ** constraints
list of current constraints
Definition: ik.h:230
int AddConstraint(IKConstraint *_constraint)
Definition: ik.cpp:428
#define DEFAULT_MAX_INTEG_ERROR
Definition: chain.h:32
int LoadMarkerXML(const char *fname, const char *_charname)
Load marker information from XML file.
IKConstraint * FindConstraint(ConstType _type, const char *jname, const char *charname=0)
Definition: ik.cpp:465
void SetMaxConditionNumber(double cn)
Set maximum condition number.
Definition: ik.h:169
void SetDesire(double _q)
Definition: ik.h:622
Desired joint values.
Definition: ik.h:555
virtual int calc_jacobian_rotate(Joint *cur)
Definition: ik.h:369
strictly satisfied
Definition: ik.h:58
Joint * GetJoint()
Definition: ik.h:344
void set_character_scale(Joint *jnt, double _scale, const char *charname)
Definition: ik.cpp:623
void SetConstraintScale(double _scale, const char *charname=0)
Set constraint scale parameter.
Definition: ik.cpp:614
double gain
priority
Definition: ik.h:396
int active
Definition: ik.h:400
int Dropped()
Definition: ik.h:350
IKHandle * add_marker(const char *marker_name, Joint *parent_joint, const fVec3 &abs_pos)
Definition: ik.cpp:282
IK::Priority priority
Definition: ik.h:395
int id
ID (unique to each constraint)
Definition: ik.h:393
IK::ConstType GetType()
Returns the constraint type.
Definition: ik.h:522
void set(double *v)
Set element values from array or three values.
Definition: fMatrix3.h:314
fVec3 pos_des
desired joint position for 6DOF joints
Definition: ik.h:647
png_uint_32 i
Definition: png.h:2735
IKDesire(IK *_ik, const char *_jname, Joint *_jnt, IK::Priority _pri, double _gain)
Definition: ik.h:560
with constraint
Definition: ik.h:67
int Active()
whether the constraint is activate
Definition: ik.h:315
fMat J[N_PRIORITY_TYPES]
Jacobian matrix of each type.
Definition: ik.h:235
int i_const
feedback velocity (n_const)
Definition: ik.h:404
IK::ConstType GetType()
Returns the constraint type.
Definition: ik.h:744
double q_des
desired joint value for 1DOF joints
Definition: ik.h:645
char * joint_name
Definition: ik.h:392
int SaveMarkers(const char *fname)
Definition: ik.cpp:336
fMat33 att_des
desired joint orientation for 3/6 DOF joints
Definition: ik.h:646
spherical (3DOF)
Definition: chain.h:43
int n_all_const
Definition: ik.h:239
without constraint
Definition: ik.h:68
void zero()
Creates a zero matrix.
Definition: fMatrix.h:249
fVec joint_weights
joint weights
Definition: ik.h:245
void GetConstIndex(IK::ConstIndex _cindex[])
Definition: ik.h:526
void CalcPosition()
Forward kinematics.
Definition: fk.cpp:16
fVec weight
feedback gain
Definition: ik.h:397
int marker
Definition: jpeglib.h:950
int assign_constraints(int _n)
Definition: ik.cpp:402
desired joint values
Definition: ik.h:49
Joint * joint
target joint
Definition: ik.h:391
~IKCom()
Definition: ik.h:684
virtual int calc_jacobian_slide(Joint *cur)
Definition: ik.h:372
int Reset()
Definition: ik.h:691
IKHandle(IK *_ik, const char *_jname, Joint *_jnt, IK::ConstIndex cindex[6], IK::Priority _pri, double _gain, const fVec3 &_rel_pos=0.0, const fMat33 &_rel_att=1.0, Joint *_other_joint=0)
Definition: ik.h:433
strictly satisfied if possible
Definition: ik.h:59
int calc_jacobian()
compute the Jacobian matrix
Definition: update_ik.cpp:66
fMat J
Definition: ik.h:402
fVec fb
Jacobian matrix (n_const x total DOF)
Definition: ik.h:403
fMat33 rel_att
Definition: ik.h:545
void SetCharacterScale(double _scale, const char *charname=0)
Set character scale parameter.
Definition: ik.cpp:605
void SetMin(double _q_min)
Definition: ik.h:752
fVec3 abs_pos
current constraint position
Definition: ik.h:540
virtual int Reset()
Definition: ik.h:293
t
int Reset()
reset the constraint position/orientation by the current values
Definition: ik.h:478
~IKScalarJointLimit()
Definition: ik.h:741
int is_dropped
index in the constraints with the same priority
Definition: ik.h:406
lower priority
Definition: ik.h:60
int nConst()
Definition: ik.h:340
void Diactivate()
diactivate the constraint
Definition: ik.h:311
int ID()
Definition: ik.h:347
~IKHandle()
Definition: ik.h:474
void resize(int i)
Change the size.
Definition: fMatrix.h:511
Vector of generic size.
Definition: fMatrix.h:491
IK::Priority GetPriority()
get the priproty
Definition: ik.h:333
Classes for defining open/closed kinematic chains.
joint limit for rotate and slide joints
Definition: ik.h:51
void SetAtt(const fMat33 &_abs_att)
set the constraint orientation
Definition: ik.h:503
int enabled
number of constraints
Definition: ik.h:399
IKCom(IK *_ik, const char *_charname, IK::ConstIndex cindex[3], IK::Priority _pri, double _gain)
Definition: ik.h:658
~IKDesire()
Definition: ik.h:593
double max_condnum
maximum condition number
Definition: ik.h:242
double Update(double timestep)
Definition: update_ik.cpp:24
id
prismatic (1DOF)
Definition: chain.h:42
void SetPos(const fVec3 &p)
Definition: ik.h:695
~IK()
Destructor.
Definition: ik.cpp:29
int RemoveConstraint(int _id)
Definition: ik.cpp:439
ConstIndex
Definition: ik.h:66
void SetDesire(const fVec3 &_pos, const fMat33 &_att)
Definition: ik.h:628
int myinit(SceneGraph *sg)
Definition: ik.cpp:70
The class representing the whole mechanism. May contain multiple characters.
Definition: chain.h:144
void zero()
Creates a zero vector.
Definition: fMatrix.h:575
static const char joint_name_separator
Definition: ik.h:31
Joint limit constraint for 1-DOF joints.
Definition: ik.h:713
void sub(const fVec3 &vec1, const fVec3 &vec2)
Definition: fMatrix3.cpp:902
int NumConstraints()
Number of constraints.
Definition: ik.h:77
fVec3 cur_com
current COM position
Definition: ik.h:706
position/orientation of link
Definition: ik.h:48
IK * ik
Definition: ik.h:390
IKScalarJointLimit(IK *_ik, const char *_jname, Joint *_jnt, IK::Priority _pri, double _gain)
Definition: ik.h:718
virtual void SetCharacterScale(double _scale, const char *charname=0)
Definition: ik.h:355
int n_total_const
number of total constraints used so far, including removed ones
Definition: ik.h:227
virtual int calc_jacobian_free(Joint *cur)
Definition: ik.h:378
3-element vector class.
Definition: fMatrix3.h:206
double GetGain()
get the gain
Definition: ik.h:324
IK::ConstType GetType()
Returns the constraint type.
Definition: ik.h:618
int load_markers(SceneGraph *sg, Joint *rj)
Definition: ik.cpp:89
double q_min
Definition: ik.h:771
rotational (1DOF)
Definition: chain.h:41
void GetAtt(fMat33 &_abs_att)
obtain constraint orientation
Definition: ik.h:512
void SetDesire(const fMat33 &_att)
Definition: ik.h:625
int n_const
weight
Definition: ik.h:398
int n_assigned_constraints
Definition: ik.h:232
void Activate()
activate the constraint
Definition: ik.h:307
The class for representing a joint.
Definition: chain.h:538
int ResetConstraints(ConstType t)
Reset the constraints with the specific type.
Definition: ik.cpp:540
int copy_jacobian()
Definition: update_ik.cpp:125
IK::ConstType GetType()
Returns the constraint type.
Definition: ik.h:688
void GetPos(fVec3 &_abs_pos)
obtain constraint position
Definition: ik.h:508
int DisableDesire(const char *jname)
Disable desire constraint of the specific joint.
Definition: ik.cpp:596
double GetMin()
Definition: ik.h:759
IKConstraint(IK *_ik, const char *_jname, Joint *_jnt, IK::Priority _pri, double _gain)
Default constructor.
Definition: ik.h:266
int Reset()
Definition: ik.h:596
int EditMarker(IKHandle *marker, const char *body_name, Joint *parent_joint, const fVec3 &abs_pos=0.0)
Definition: ik.cpp:295
int iConst()
Definition: ik.h:337
Center of mass position.
Definition: ik.h:654
int calc_feedback()
Definition: update_ik.cpp:112
int EnableDesire(const char *jname)
Enable desire constraint of the specific joint.
Definition: ik.cpp:587
void SetPos(const fVec3 &_abs_pos)
set the constraint position
Definition: ik.h:499
int save_marker(TransformNode *top_tnode, IKHandle *h)
Definition: ik.cpp:357
fVec weight[N_PRIORITY_TYPES]
weight of each type
Definition: ik.h:237
virtual ~IKConstraint()
Destructor.
Definition: ik.h:286
void SetMax(double _q_max)
Definition: ik.h:748
void Disable()
disable the constraint
Definition: ik.h:302
free (6DOF)
Definition: chain.h:44
ConstType
Definition: ik.h:47
Main class for inverse kinematic computation.
Definition: ik.h:37
Matrix of generic size. The elements are stored in a one-dimensional array in row-major order...
Definition: fMatrix.h:46
void SetDesire(const fVec3 &_pos)
Definition: ik.h:632
fVec fb[N_PRIORITY_TYPES]
constraint error of each type
Definition: ik.h:236
void SetPriority(IK::Priority _pri)
set the priproty
Definition: ik.h:329
Joint * other_joint
connected to other joint: constrains the relative position and/or orientation w.r.t. other_joint&#39;s frame
Definition: ik.h:548
int ConstraintID(ConstType _type, const char *jname)
Definition: ik.cpp:493
double GetMax()
Definition: ik.h:756


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