2 * ***** BEGIN GPL LICENSE BLOCK *****
4 * This program is free software; you can redistribute it and/or
5 * modify it under the terms of the GNU General Public License
6 * as published by the Free Software Foundation; either version 2
7 * of the License, or (at your option) any later version.
9 * This program is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with this program; if not, write to the Free Software Foundation,
16 * Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18 * The Original Code is Copyright (C) 2001-2002 by NaN Holding BV.
19 * All rights reserved.
21 * The Original Code is: all of this file.
23 * Original author: Benoit Bolsee
26 * ***** END GPL LICENSE BLOCK *****
29 /** \file blender/ikplugin/intern/itasc_plugin.cpp
39 #include "Armature.hpp"
40 #include "MovingFrame.hpp"
41 #include "CopyPose.hpp"
42 #include "WSDLSSolver.hpp"
43 #include "WDLSSolver.hpp"
46 #include "Distance.hpp"
49 #include "MEM_guardedalloc.h"
53 #include "BLI_blenlib.h"
55 #include "BLI_utildefines.h"
57 #include "BKE_global.h"
58 #include "BKE_armature.h"
59 #include "BKE_action.h"
60 #include "BKE_constraint.h"
61 #include "DNA_object_types.h"
62 #include "DNA_action_types.h"
63 #include "DNA_constraint_types.h"
64 #include "DNA_armature_types.h"
65 #include "DNA_scene_types.h"
68 #include "itasc_plugin.h"
73 // in case of animation mode, feedback and timestep is fixed
74 #define ANIM_TIMESTEP 1.0
75 #define ANIM_FEEDBACK 0.8
76 #define ANIM_QMAX 0.52
79 // Structure pointed by bPose.ikdata
80 // It contains everything needed to simulate the armatures
81 // There can be several simulation islands independent to each other
83 struct IK_Scene *first;
86 typedef float Vector3[3];
87 typedef float Vector4[4];
89 typedef void (*ErrorCallback)(const iTaSC::ConstraintValues *values, unsigned int nvalues, IK_Target *iktarget);
91 // one structure for each target in the scene
94 struct Scene *blscene;
95 iTaSC::MovingFrame* target;
96 iTaSC::ConstraintSet* constraint;
97 struct bConstraint* blenderConstraint;
98 struct bPoseChannel* rootChannel;
99 Object* owner; //for auto IK
100 ErrorCallback errorCallback;
101 std::string targetName;
102 std::string constraintName;
103 unsigned short controlType;
104 short channel; //index in IK channel array of channel on which this target is defined
105 short ee; //end effector number
106 bool simulation; //true when simulation mode is used (update feedback)
107 bool eeBlend; //end effector affected by enforce blending
108 float eeRest[4][4]; //end effector initial pose relative to armature
114 blenderConstraint = NULL;
122 targetName.reserve(32);
123 constraintName.reserve(32);
134 bPoseChannel* pchan; // channel where we must copy matrix back
135 KDL::Frame frame; // frame of the bone relative to object base, not armature base
136 std::string tail; // segment name of the joint from which we get the bone tail
137 std::string head; // segment name of the joint from which we get the bone head
138 int parent; // index in this array of the parent channel
139 short jointType; // type of joint, combination of IK_SegmentFlag
140 char ndof; // number of joint angles for this channel
141 char jointValid; // set to 1 when jointValue has been computed
142 // for joint constraint
143 Object* owner; // for pose and IK param
144 double jointValue[4]; // computed joint value
161 struct Scene *blscene;
163 int numchan; // number of channel in pchan
164 int numjoint; // number of joint in jointArray
165 // array of bone information, one per channel in the tree
166 IK_Channel* channels;
167 iTaSC::Armature* armature;
170 iTaSC::MovingFrame* base; // armature base object
171 KDL::Frame baseFrame; // frame of armature base relative to blArmature
172 KDL::JntArray jointArray; // buffer for storing temporary joint array
173 iTaSC::Solver* solver;
175 float blScale; // scale of the Armature object (assume uniform scaling)
176 float blInvScale; // inverse of Armature object scale
177 struct bConstraint* polarConstraint;
178 std::vector<IK_Target*> targets;
189 blScale = blInvScale = 1.0f;
193 polarConstraint = NULL;
197 // delete scene first
200 for (std::vector<IK_Target *>::iterator it = targets.begin(); it != targets.end(); ++it)
217 // type of IK joint, can be combined to list the joints corresponding to a bone
218 enum IK_SegmentFlag {
227 enum IK_SegmentAxis {
236 static int initialize_chain(Object *ob, bPoseChannel *pchan_tip, bConstraint *con)
238 bPoseChannel *curchan, *pchan_root = NULL, *chanlist[256], **oldchan;
241 bKinematicConstraint *data;
242 int a, t, segcount = 0, size, newsize, *oldparent, parent, rootbone, treecount;
244 data = (bKinematicConstraint *)con->data;
246 /* exclude tip from chain? */
247 if (!(data->flag & CONSTRAINT_IK_TIP))
248 pchan_tip = pchan_tip->parent;
250 rootbone = data->rootbone;
251 /* Find the chain's root & count the segments needed */
252 for (curchan = pchan_tip; curchan; curchan = curchan->parent) {
253 pchan_root = curchan;
255 if (++segcount > 255) // 255 is weak
258 if (segcount == rootbone) {
259 // reached this end of the chain but if the chain is overlapping with a
260 // previous one, we must go back up to the root of the other chain
261 if ((curchan->flag & POSE_CHAIN) && curchan->iktree.first == NULL) {
268 if (curchan->iktree.first != NULL)
269 // Oh oh, there is already a chain starting from this channel and our chain is longer...
270 // Should handle this by moving the previous chain up to the beginning of our chain
271 // For now we just stop here
274 if (!segcount) return 0;
275 // we reached a limit and still not the end of a previous chain, quit
276 if ((pchan_root->flag & POSE_CHAIN) && pchan_root->iktree.first == NULL) return 0;
278 // now that we know how many segment we have, set the flag
279 for (rootbone = segcount, segcount = 0, curchan = pchan_tip; segcount < rootbone; segcount++, curchan = curchan->parent) {
280 chanlist[segcount] = curchan;
281 curchan->flag |= POSE_CHAIN;
284 /* setup the chain data */
285 /* create a target */
286 target = (PoseTarget *)MEM_callocN(sizeof(PoseTarget), "posetarget");
288 // by contruction there can be only one tree per channel and each channel can be part of at most one tree.
289 tree = (PoseTree *)pchan_root->iktree.first;
293 tree = (PoseTree *)MEM_callocN(sizeof(PoseTree), "posetree");
295 tree->iterations = data->iterations;
296 tree->totchannel = segcount;
297 tree->stretch = (data->flag & CONSTRAINT_IK_STRETCH);
299 tree->pchan = (bPoseChannel **)MEM_callocN(segcount * sizeof(void *), "ik tree pchan");
300 tree->parent = (int *)MEM_callocN(segcount * sizeof(int), "ik tree parent");
301 for (a = 0; a < segcount; a++) {
302 tree->pchan[a] = chanlist[segcount - a - 1];
303 tree->parent[a] = a - 1;
305 target->tip = segcount - 1;
307 /* AND! link the tree to the root */
308 BLI_addtail(&pchan_root->iktree, tree);
313 tree->iterations = MAX2(data->iterations, tree->iterations);
314 tree->stretch = tree->stretch && !(data->flag & CONSTRAINT_IK_STRETCH);
316 /* skip common pose channels and add remaining*/
317 size = MIN2(segcount, tree->totchannel);
319 while (a < size && t < tree->totchannel) {
320 // locate first matching channel
321 for (; t < tree->totchannel && tree->pchan[t] != chanlist[segcount - a - 1]; t++) ;
322 if (t >= tree->totchannel)
324 for (; a < size && t < tree->totchannel && tree->pchan[t] == chanlist[segcount - a - 1]; a++, t++) ;
327 segcount = segcount - a;
328 target->tip = tree->totchannel + segcount - 1;
331 for (parent = a - 1; parent < tree->totchannel; parent++)
332 if (tree->pchan[parent] == chanlist[segcount - 1]->parent)
335 /* shouldn't happen, but could with dependency cycles */
336 if (parent == tree->totchannel)
340 newsize = tree->totchannel + segcount;
341 oldchan = tree->pchan;
342 oldparent = tree->parent;
344 tree->pchan = (bPoseChannel **)MEM_callocN(newsize * sizeof(void *), "ik tree pchan");
345 tree->parent = (int *)MEM_callocN(newsize * sizeof(int), "ik tree parent");
346 memcpy(tree->pchan, oldchan, sizeof(void *) * tree->totchannel);
347 memcpy(tree->parent, oldparent, sizeof(int) * tree->totchannel);
349 MEM_freeN(oldparent);
351 /* add new pose channels at the end, in reverse order */
352 for (a = 0; a < segcount; a++) {
353 tree->pchan[tree->totchannel + a] = chanlist[segcount - a - 1];
354 tree->parent[tree->totchannel + a] = tree->totchannel + a - 1;
356 tree->parent[tree->totchannel] = parent;
358 tree->totchannel = newsize;
364 /* add target to the tree */
365 BLI_addtail(&tree->targets, target);
366 /* mark root channel having an IK tree */
367 pchan_root->flag |= POSE_IKTREE;
371 static bool is_cartesian_constraint(bConstraint *con)
373 //bKinematicConstraint* data=(bKinematicConstraint*)con->data;
378 static bool constraint_valid(bConstraint *con)
380 bKinematicConstraint *data = (bKinematicConstraint *)con->data;
382 if (data->flag & CONSTRAINT_IK_AUTO)
384 if (con->flag & CONSTRAINT_DISABLE)
386 if (is_cartesian_constraint(con)) {
387 /* cartesian space constraint */
388 if (data->tar == NULL)
390 if (data->tar->type == OB_ARMATURE && data->subtarget[0] == 0)
396 static int initialize_scene(Object *ob, bPoseChannel *pchan_tip)
401 /* find all IK constraints and validate them */
403 for (con = (bConstraint *)pchan_tip->constraints.first; con; con = (bConstraint *)con->next) {
404 if (con->type == CONSTRAINT_TYPE_KINEMATIC) {
405 if (constraint_valid(con))
406 treecount += initialize_chain(ob, pchan_tip, con);
412 static IK_Data *get_ikdata(bPose *pose)
415 return (IK_Data *)pose->ikdata;
416 pose->ikdata = MEM_callocN(sizeof(IK_Data), "iTaSC ikdata");
417 // here init ikdata if needed
418 // now that we have scene, make sure the default param are initialized
419 if (!DefIKParam.iksolver)
420 BKE_pose_itasc_init(&DefIKParam);
422 return (IK_Data *)pose->ikdata;
424 static double EulerAngleFromMatrix(const KDL::Rotation& R, int axis)
426 double t = KDL::sqrt(R(0, 0) * R(0, 0) + R(0, 1) * R(0, 1));
428 if (t > 16.0 * KDL::epsilon) {
429 if (axis == 0) return -KDL::atan2(R(1, 2), R(2, 2));
430 else if (axis == 1) return KDL::atan2(-R(0, 2), t);
431 else return -KDL::atan2(R(0, 1), R(0, 0));
434 if (axis == 0) return -KDL::atan2(-R(2, 1), R(1, 1));
435 else if (axis == 1) return KDL::atan2(-R(0, 2), t);
440 static double ComputeTwist(const KDL::Rotation& R)
442 // qy and qw are the y and w components of the quaternion from R
443 double qy = R(0, 2) - R(2, 0);
444 double qw = R(0, 0) + R(1, 1) + R(2, 2) + 1;
446 double tau = 2 * KDL::atan2(qy, qw);
451 static void RemoveEulerAngleFromMatrix(KDL::Rotation& R, double angle, int axis)
453 // compute twist parameter
457 T = KDL::Rotation::RotX(-angle);
460 T = KDL::Rotation::RotY(-angle);
463 T = KDL::Rotation::RotZ(-angle);
473 static void GetEulerXZY(const KDL::Rotation& R, double& X, double& Z, double& Y)
475 if (fabs(R(0, 1)) > 1.0 - KDL::epsilon) {
476 X = -KDL::sign(R(0, 1)) * KDL::atan2(R(1, 2), R(1, 0));
477 Z = -KDL::sign(R(0, 1)) * KDL::PI / 2;
481 X = KDL::atan2(R(2, 1), R(1, 1));
482 Z = KDL::atan2(-R(0, 1), KDL::sqrt(KDL::sqr(R(0, 0)) + KDL::sqr(R(0, 2))));
483 Y = KDL::atan2(R(0, 2), R(0, 0));
487 static void GetEulerXYZ(const KDL::Rotation& R, double& X, double& Y, double& Z)
489 if (fabs(R(0, 2)) > 1.0 - KDL::epsilon) {
490 X = KDL::sign(R(0, 2)) * KDL::atan2(-R(1, 0), R(1, 1));
491 Y = KDL::sign(R(0, 2)) * KDL::PI / 2;
495 X = KDL::atan2(-R(1, 2), R(2, 2));
496 Y = KDL::atan2(R(0, 2), KDL::sqrt(KDL::sqr(R(0, 0)) + KDL::sqr(R(0, 1))));
497 Z = KDL::atan2(-R(0, 1), R(0, 0));
502 static void GetJointRotation(KDL::Rotation& boneRot, int type, double *rot)
504 switch (type & ~IK_TRANSY) {
506 // fixed bone, no joint
509 // RX only, get the X rotation
510 rot[0] = EulerAngleFromMatrix(boneRot, 0);
513 // RY only, get the Y rotation
514 rot[0] = ComputeTwist(boneRot);
517 // RZ only, get the Z rotation
518 rot[0] = EulerAngleFromMatrix(boneRot, 2);
520 case IK_XDOF | IK_YDOF:
521 rot[1] = ComputeTwist(boneRot);
522 RemoveEulerAngleFromMatrix(boneRot, rot[1], 1);
523 rot[0] = EulerAngleFromMatrix(boneRot, 0);
527 boneRot.GetXZRot().GetValue(rot);
529 case IK_YDOF | IK_ZDOF:
531 rot[1] = ComputeTwist(boneRot);
532 RemoveEulerAngleFromMatrix(boneRot, rot[1], 1);
533 rot[0] = EulerAngleFromMatrix(boneRot, 2);
535 case IK_SWING | IK_YDOF:
536 rot[2] = ComputeTwist(boneRot);
537 RemoveEulerAngleFromMatrix(boneRot, rot[2], 1);
538 boneRot.GetXZRot().GetValue(rot);
541 boneRot.GetRot().GetValue(rot);
546 static bool target_callback(const iTaSC::Timestamp& timestamp, const iTaSC::Frame& current, iTaSC::Frame& next, void *param)
548 IK_Target *target = (IK_Target *)param;
549 // compute next target position
550 // get target matrix from constraint.
551 bConstraint *constraint = (bConstraint *)target->blenderConstraint;
554 get_constraint_target_matrix(target->blscene, constraint, 0, CONSTRAINT_OBTYPE_OBJECT, target->owner, tarmat, 1.0);
556 // rootmat contains the target pose in world coordinate
557 // if enforce is != 1.0, blend the target position with the end effector position
558 // if the armature was in rest position. This information is available in eeRest
559 if (constraint->enforce != 1.0f && target->eeBlend) {
560 // eeRest is relative to the reference frame of the IK root
561 // get this frame in world reference
563 bPoseChannel *pchan = target->rootChannel;
565 pchan = pchan->parent;
567 copy_m4_m4(chanmat, pchan->pose_mat);
568 copy_v3_v3(chanmat[3], pchan->pose_tail);
569 mul_serie_m4(restmat, target->owner->obmat, chanmat, target->eeRest, NULL, NULL, NULL, NULL, NULL);
572 mult_m4_m4m4(restmat, target->owner->obmat, target->eeRest);
575 blend_m4_m4m4(tarmat, restmat, tarmat, constraint->enforce);
577 next.setValue(&tarmat[0][0]);
581 static bool base_callback(const iTaSC::Timestamp& timestamp, const iTaSC::Frame& current, iTaSC::Frame& next, void *param)
583 IK_Scene *ikscene = (IK_Scene *)param;
584 // compute next armature base pose
586 // ikscene->pchan[0] is the root channel of the tree
587 // if it has a parent, get the pose matrix from it and replace [3] by parent pchan->tail
588 // then multiply by the armature matrix to get ikscene->armature base position
589 bPoseChannel *pchan = ikscene->channels[0].pchan;
592 pchan = pchan->parent;
594 copy_m4_m4(chanmat, pchan->pose_mat);
595 copy_v3_v3(chanmat[3], pchan->pose_tail);
596 // save the base as a frame too so that we can compute deformation after simulation
597 ikscene->baseFrame.setValue(&chanmat[0][0]);
598 // iTaSC armature is scaled to object scale, scale the base frame too
599 ikscene->baseFrame.p *= ikscene->blScale;
600 mult_m4_m4m4(rootmat, ikscene->blArmature->obmat, chanmat);
603 copy_m4_m4(rootmat, ikscene->blArmature->obmat);
604 ikscene->baseFrame = iTaSC::F_identity;
606 next.setValue(&rootmat[0][0]);
607 // if there is a polar target (only during solving otherwise we don't have end efffector)
608 if (ikscene->polarConstraint && timestamp.update) {
609 // compute additional rotation of base frame so that armature follows the polar target
610 float imat[4][4]; // IK tree base inverse matrix
611 float polemat[4][4]; // polar target in IK tree base frame
612 float goalmat[4][4]; // target in IK tree base frame
613 float mat[4][4]; // temp matrix
614 bKinematicConstraint *poledata = (bKinematicConstraint *)ikscene->polarConstraint->data;
616 invert_m4_m4(imat, rootmat);
617 // polar constraint imply only one target
618 IK_Target *iktarget = ikscene->targets[0];
619 // root channel from which we take the bone initial orientation
620 IK_Channel &rootchan = ikscene->channels[0];
622 // get polar target matrix in world space
623 get_constraint_target_matrix(ikscene->blscene, ikscene->polarConstraint, 1, CONSTRAINT_OBTYPE_OBJECT, ikscene->blArmature, mat, 1.0);
624 // convert to armature space
625 mult_m4_m4m4(polemat, imat, mat);
626 // get the target in world space (was computed before as target object are defined before base object)
627 iktarget->target->getPose().getValue(mat[0]);
628 // convert to armature space
629 mult_m4_m4m4(goalmat, imat, mat);
630 // take position of target, polar target, end effector, in armature space
631 KDL::Vector goalpos(goalmat[3]);
632 KDL::Vector polepos(polemat[3]);
633 KDL::Vector endpos = ikscene->armature->getPose(iktarget->ee).p;
634 // get root bone orientation
635 KDL::Frame rootframe;
636 ikscene->armature->getRelativeFrame(rootframe, rootchan.tail);
637 KDL::Vector rootx = rootframe.M.UnitX();
638 KDL::Vector rootz = rootframe.M.UnitZ();
639 // and compute root bone head
640 double q_rest[3], q[3], length;
641 const KDL::Joint *joint;
642 const KDL::Frame *tip;
643 ikscene->armature->getSegment(rootchan.tail, 3, joint, q_rest[0], q[0], tip);
644 length = (joint->getType() == KDL::Joint::TransY) ? q[0] : tip->p(1);
645 KDL::Vector rootpos = rootframe.p - length *rootframe.M.UnitY();
647 // compute main directions
648 KDL::Vector dir = KDL::Normalize(endpos - rootpos);
649 KDL::Vector poledir = KDL::Normalize(goalpos - rootpos);
650 // compute up directions
651 KDL::Vector poleup = KDL::Normalize(polepos - rootpos);
652 KDL::Vector up = rootx * KDL::cos(poledata->poleangle) + rootz *KDL::sin(poledata->poleangle);
653 // from which we build rotation matrix
654 KDL::Rotation endrot, polerot;
655 // for the armature, using the root bone orientation
656 KDL::Vector x = KDL::Normalize(dir * up);
658 endrot.UnitY(KDL::Normalize(x * dir));
660 // for the polar target
661 x = KDL::Normalize(poledir * poleup);
663 polerot.UnitY(KDL::Normalize(x * poledir));
664 polerot.UnitZ(-poledir);
665 // the difference between the two is the rotation we want to apply
666 KDL::Rotation result(polerot * endrot.Inverse());
667 // apply on base frame as this is an artificial additional rotation
668 next.M = next.M * result;
669 ikscene->baseFrame.M = ikscene->baseFrame.M * result;
674 static bool copypose_callback(const iTaSC::Timestamp& timestamp, iTaSC::ConstraintValues *const _values, unsigned int _nvalues, void *_param)
676 IK_Target *iktarget = (IK_Target *)_param;
677 bKinematicConstraint *condata = (bKinematicConstraint *)iktarget->blenderConstraint->data;
678 iTaSC::ConstraintValues *values = _values;
679 bItasc *ikparam = (bItasc *) iktarget->owner->pose->ikparam;
681 // we need default parameters
683 ikparam = &DefIKParam;
685 if (iktarget->blenderConstraint->flag & CONSTRAINT_OFF) {
686 if (iktarget->controlType & iTaSC::CopyPose::CTL_POSITION) {
688 values->action = iTaSC::ACT_ALPHA;
691 if (iktarget->controlType & iTaSC::CopyPose::CTL_ROTATION) {
693 values->action = iTaSC::ACT_ALPHA;
698 if (iktarget->controlType & iTaSC::CopyPose::CTL_POSITION) {
700 values->alpha = condata->weight;
701 values->action = iTaSC::ACT_ALPHA | iTaSC::ACT_FEEDBACK;
702 values->feedback = (iktarget->simulation) ? ikparam->feedback : ANIM_FEEDBACK;
705 if (iktarget->controlType & iTaSC::CopyPose::CTL_ROTATION) {
707 values->alpha = condata->orientweight;
708 values->action = iTaSC::ACT_ALPHA | iTaSC::ACT_FEEDBACK;
709 values->feedback = (iktarget->simulation) ? ikparam->feedback : ANIM_FEEDBACK;
716 static void copypose_error(const iTaSC::ConstraintValues *values, unsigned int nvalues, IK_Target *iktarget)
718 iTaSC::ConstraintSingleValue *value;
722 if (iktarget->controlType & iTaSC::CopyPose::CTL_POSITION) {
724 for (i = 0, error = 0.0, value = values->values; i < values->number; ++i, ++value)
725 error += KDL::sqr(value->y - value->yd);
726 iktarget->blenderConstraint->lin_error = (float)KDL::sqrt(error);
729 if (iktarget->controlType & iTaSC::CopyPose::CTL_ROTATION) {
731 for (i = 0, error = 0.0, value = values->values; i < values->number; ++i, ++value)
732 error += KDL::sqr(value->y - value->yd);
733 iktarget->blenderConstraint->rot_error = (float)KDL::sqrt(error);
738 static bool distance_callback(const iTaSC::Timestamp& timestamp, iTaSC::ConstraintValues *const _values, unsigned int _nvalues, void *_param)
740 IK_Target *iktarget = (IK_Target *)_param;
741 bKinematicConstraint *condata = (bKinematicConstraint *)iktarget->blenderConstraint->data;
742 iTaSC::ConstraintValues *values = _values;
743 bItasc *ikparam = (bItasc *) iktarget->owner->pose->ikparam;
744 // we need default parameters
746 ikparam = &DefIKParam;
748 // update weight according to mode
749 if (iktarget->blenderConstraint->flag & CONSTRAINT_OFF) {
753 switch (condata->mode) {
754 case LIMITDIST_INSIDE:
755 values->alpha = (values->values[0].y > condata->dist) ? condata->weight : 0.0;
757 case LIMITDIST_OUTSIDE:
758 values->alpha = (values->values[0].y < condata->dist) ? condata->weight : 0.0;
761 values->alpha = condata->weight;
764 if (!timestamp.substep) {
765 // only update value on first timestep
766 switch (condata->mode) {
767 case LIMITDIST_INSIDE:
768 values->values[0].yd = condata->dist * 0.95;
770 case LIMITDIST_OUTSIDE:
771 values->values[0].yd = condata->dist * 1.05;
774 values->values[0].yd = condata->dist;
777 values->values[0].action = iTaSC::ACT_VALUE | iTaSC::ACT_FEEDBACK;
778 values->feedback = (iktarget->simulation) ? ikparam->feedback : ANIM_FEEDBACK;
781 values->action |= iTaSC::ACT_ALPHA;
785 static void distance_error(const iTaSC::ConstraintValues *values, unsigned int _nvalues, IK_Target *iktarget)
787 iktarget->blenderConstraint->lin_error = (float)(values->values[0].y - values->values[0].yd);
790 static bool joint_callback(const iTaSC::Timestamp& timestamp, iTaSC::ConstraintValues *const _values, unsigned int _nvalues, void *_param)
792 IK_Channel *ikchan = (IK_Channel *)_param;
793 bItasc *ikparam = (bItasc *)ikchan->owner->pose->ikparam;
794 bPoseChannel *chan = ikchan->pchan;
797 // a channel can be splitted into multiple joints, so we get called multiple
798 // times for one channel (this callback is only for 1 joint in the armature)
799 // the IK_JointTarget structure is shared between multiple joint constraint
800 // and the target joint values is computed only once, remember this in jointValid
801 // Don't forget to reset it before each frame
802 if (!ikchan->jointValid) {
805 if (chan->rotmode > 0) {
806 /* euler rotations (will cause gimble lock, but this can be alleviated a bit with rotation orders) */
807 eulO_to_mat3(rmat, chan->eul, chan->rotmode);
809 else if (chan->rotmode == ROT_MODE_AXISANGLE) {
810 /* axis-angle - stored in quaternion data, but not really that great for 3D-changing orientations */
811 axis_angle_to_mat3(rmat, &chan->quat[1], chan->quat[0]);
814 /* quats are normalized before use to eliminate scaling issues */
815 normalize_qt(chan->quat);
816 quat_to_mat3(rmat, chan->quat);
818 KDL::Rotation jointRot(
819 rmat[0][0], rmat[1][0], rmat[2][0],
820 rmat[0][1], rmat[1][1], rmat[2][1],
821 rmat[0][2], rmat[1][2], rmat[2][2]);
822 GetJointRotation(jointRot, ikchan->jointType, ikchan->jointValue);
823 ikchan->jointValid = 1;
825 // determine which part of jointValue is used for this joint
826 // closely related to the way the joints are defined
827 switch (ikchan->jointType & ~IK_TRANSY) {
833 case IK_XDOF | IK_YDOF:
835 dof = (_values[0].id == iTaSC::Armature::ID_JOINT_RX) ? 0 : 1;
841 case IK_YDOF | IK_ZDOF:
843 dof = (_values[0].id == iTaSC::Armature::ID_JOINT_RZ) ? 0 : 1;
845 case IK_SWING | IK_YDOF:
847 dof = (_values[0].id == iTaSC::Armature::ID_JOINT_RY) ? 2 : 0;
857 for (unsigned int i = 0; i < _nvalues; i++, dof++) {
858 _values[i].values[0].yd = ikchan->jointValue[dof];
859 _values[i].alpha = chan->ikrotweight;
860 _values[i].feedback = ikparam->feedback;
866 // build array of joint corresponding to IK chain
867 static int convert_channels(IK_Scene *ikscene, PoseTree *tree)
874 for (a = 0, ikchan = ikscene->channels; a < ikscene->numchan; ++a, ++ikchan) {
875 pchan = tree->pchan[a];
876 ikchan->pchan = pchan;
877 ikchan->parent = (a > 0) ? tree->parent[a] : -1;
878 ikchan->owner = ikscene->blArmature;
882 if (!(pchan->ikflag & BONE_IK_NO_XDOF) && !(pchan->ikflag & BONE_IK_NO_XDOF_TEMP) &&
883 (!(pchan->ikflag & BONE_IK_XLIMIT) || pchan->limitmin[0] < 0.f || pchan->limitmax[0] > 0.f))
887 if (!(pchan->ikflag & BONE_IK_NO_YDOF) && !(pchan->ikflag & BONE_IK_NO_YDOF_TEMP) &&
888 (!(pchan->ikflag & BONE_IK_YLIMIT) || pchan->limitmin[1] < 0.f || pchan->limitmax[1] > 0.f))
892 if (!(pchan->ikflag & BONE_IK_NO_ZDOF) && !(pchan->ikflag & BONE_IK_NO_ZDOF_TEMP) &&
893 (!(pchan->ikflag & BONE_IK_ZLIMIT) || pchan->limitmin[2] < 0.f || pchan->limitmax[2] > 0.f))
898 if (tree->stretch && (pchan->ikstretch > 0.0)) {
902 * Logic to create the segments:
903 * RX,RY,RZ = rotational joints with no length
904 * RY(tip) = rotational joints with a fixed length arm = (0,length,0)
905 * TY = translational joint on Y axis
906 * F(pos) = fixed joint with an arm at position pos
907 * Conversion rule of the above flags:
915 * XYZ ==> full spherical unless there are limits, in which case RX+RZ+RY(tip)
916 * In case of stretch, tip=(0,0,0) and there is an additional TY joint
917 * The frame at last of these joints represents the tail of the bone.
918 * The head is computed by a reverse translation on Y axis of the bone length
919 * or in case of TY joint, by the frame at previous joint.
920 * In case of separation of bones, there is an additional F(head) joint
922 * Computing rest pose and length is complicated: the solver works in world space
924 * rest position is computed only from bone->bone_mat.
925 * bone length is computed from bone->length multiplied by the scaling factor of
926 * the armature. Non-uniform scaling will give bad result!
928 switch (flag & (IK_XDOF | IK_YDOF | IK_ZDOF)) {
930 ikchan->jointType = 0;
934 // RX only, get the X rotation
935 ikchan->jointType = IK_XDOF;
939 // RY only, get the Y rotation
940 ikchan->jointType = IK_YDOF;
944 // RZ only, get the Zz rotation
945 ikchan->jointType = IK_ZDOF;
948 case IK_XDOF | IK_YDOF:
949 ikchan->jointType = IK_XDOF | IK_YDOF;
952 case IK_XDOF | IK_ZDOF:
954 ikchan->jointType = IK_SWING;
957 case IK_YDOF | IK_ZDOF:
959 ikchan->jointType = IK_ZDOF | IK_YDOF;
962 case IK_XDOF | IK_YDOF | IK_ZDOF:
964 if (pchan->ikflag & (BONE_IK_XLIMIT | BONE_IK_YLIMIT | BONE_IK_ZLIMIT))
965 // decompose in a Swing+RotY joint
966 ikchan->jointType = IK_SWING | IK_YDOF;
968 ikchan->jointType = IK_REVOLUTE;
972 if (flag & IK_TRANSY) {
973 ikchan->jointType |= IK_TRANSY;
976 njoint += ikchan->ndof;
978 // njoint is the joint coordinate, create the Joint Array
979 ikscene->jointArray.resize(njoint);
980 ikscene->numjoint = njoint;
984 // compute array of joint value corresponding to current pose
985 static void convert_pose(IK_Scene *ikscene)
987 KDL::Rotation boneRot;
991 float rmat[4][4]; // rest pose of bone with parent taken into account
992 float bmat[4][4]; // difference
997 // assume uniform scaling and take Y scale as general scale for the armature
998 scale = len_v3(ikscene->blArmature->obmat[1]);
999 rot = ikscene->jointArray(0);
1000 for (joint = a = 0, ikchan = ikscene->channels; a < ikscene->numchan && joint < ikscene->numjoint; ++a, ++ikchan) {
1001 pchan = ikchan->pchan;
1004 if (pchan->parent) {
1006 mul_m4_m4m3(bmat, pchan->parent->pose_mat, bone->bone_mat);
1009 copy_m4_m4(bmat, bone->arm_mat);
1011 invert_m4_m4(rmat, bmat);
1012 mult_m4_m4m4(bmat, rmat, pchan->pose_mat);
1014 boneRot.setValue(bmat[0]);
1015 GetJointRotation(boneRot, ikchan->jointType, rot);
1016 if (ikchan->jointType & IK_TRANSY) {
1017 // compute actual length
1018 rot[ikchan->ndof - 1] = len_v3v3(pchan->pose_tail, pchan->pose_head) * scale;
1020 rot += ikchan->ndof;
1021 joint += ikchan->ndof;
1025 // compute array of joint value corresponding to current pose
1026 static void BKE_pose_rest(IK_Scene *ikscene)
1028 bPoseChannel *pchan;
1035 // assume uniform scaling and take Y scale as general scale for the armature
1036 scale = len_v3(ikscene->blArmature->obmat[1]);
1038 SetToZero(ikscene->jointArray);
1039 // except for transY joints
1040 rot = ikscene->jointArray(0);
1041 for (joint = a = 0, ikchan = ikscene->channels; a < ikscene->numchan && joint < ikscene->numjoint; ++a, ++ikchan) {
1042 pchan = ikchan->pchan;
1045 if (ikchan->jointType & IK_TRANSY)
1046 rot[ikchan->ndof - 1] = bone->length * scale;
1047 rot += ikchan->ndof;
1048 joint += ikchan->ndof;
1052 static IK_Scene *convert_tree(Scene *blscene, Object *ob, bPoseChannel *pchan)
1054 PoseTree *tree = (PoseTree *)pchan->iktree.first;
1056 bKinematicConstraint *condata;
1057 bConstraint *polarcon;
1059 iTaSC::Armature *arm;
1060 iTaSC::Scene *scene;
1063 KDL::Frame initPose;
1064 KDL::Rotation boneRot;
1069 bool ret = true, ingame;
1072 if (tree->totchannel == 0)
1075 ikscene = new IK_Scene;
1076 ikscene->blscene = blscene;
1077 arm = new iTaSC::Armature();
1078 scene = new iTaSC::Scene();
1079 ikscene->channels = new IK_Channel[tree->totchannel];
1080 ikscene->numchan = tree->totchannel;
1081 ikscene->armature = arm;
1082 ikscene->scene = scene;
1083 ikparam = (bItasc *)ob->pose->ikparam;
1084 ingame = (ob->pose->flag & POSE_GAME_ENGINE);
1086 // you must have our own copy
1087 ikparam = &DefIKParam;
1090 // tweak the param when in game to have efficient stepping
1091 // using fixed substep is not effecient since frames in the GE are often
1092 // shorter than in animation => move to auto step automatically and set
1093 // the target substep duration via min/max
1094 if (!(ikparam->flag & ITASC_AUTO_STEP)) {
1095 float timestep = blscene->r.frs_sec_base / blscene->r.frs_sec;
1096 if (ikparam->numstep > 0)
1097 timestep /= ikparam->numstep;
1098 // with equal min and max, the algorythm will take this step and the indicative substep most of the time
1099 ikparam->minstep = ikparam->maxstep = timestep;
1100 ikparam->flag |= ITASC_AUTO_STEP;
1103 if ((ikparam->flag & ITASC_SIMULATION) && !ingame)
1104 // no cache in animation mode
1105 ikscene->cache = new iTaSC::Cache();
1107 switch (ikparam->solver) {
1108 case ITASC_SOLVER_SDLS:
1109 ikscene->solver = new iTaSC::WSDLSSolver();
1111 case ITASC_SOLVER_DLS:
1112 ikscene->solver = new iTaSC::WDLSSolver();
1118 ikscene->blArmature = ob;
1119 // assume uniform scaling and take Y scale as general scale for the armature
1120 ikscene->blScale = len_v3(ob->obmat[1]);
1121 ikscene->blInvScale = (ikscene->blScale < KDL::epsilon) ? 0.0f : 1.0f / ikscene->blScale;
1124 std::string root("root");
1126 std::vector<double> weights;
1128 // build the array of joints corresponding to the IK chain
1129 convert_channels(ikscene, tree);
1131 // in the GE, set the initial joint angle to match the current pose
1132 // this will update the jointArray in ikscene
1133 convert_pose(ikscene);
1136 // in Blender, the rest pose is always 0 for joints
1137 BKE_pose_rest(ikscene);
1139 rot = ikscene->jointArray(0);
1140 for (a = 0, ikchan = ikscene->channels; a < tree->totchannel; ++a, ++ikchan) {
1141 pchan = ikchan->pchan;
1144 KDL::Frame tip(iTaSC::F_identity);
1145 Vector3 *fl = bone->bone_mat;
1147 fl[0][0], fl[1][0], fl[2][0],
1148 fl[0][1], fl[1][1], fl[2][1],
1149 fl[0][2], fl[1][2], fl[2][2]);
1150 KDL::Vector bpos(bone->head[0], bone->head[1], bone->head[2]);
1151 bpos *= ikscene->blScale;
1152 KDL::Frame head(brot, bpos);
1154 // rest pose length of the bone taking scaling into account
1155 length = bone->length * ikscene->blScale;
1156 parent = (a > 0) ? ikscene->channels[tree->parent[a]].tail : root;
1157 // first the fixed segment to the bone head
1158 if (head.p.Norm() > KDL::epsilon || head.M.GetRot().Norm() > KDL::epsilon) {
1161 ret = arm->addSegment(joint, parent, KDL::Joint::None, 0.0, head);
1164 if (!(ikchan->jointType & IK_TRANSY)) {
1165 // fixed length, put it in tip
1169 weight[0] = (1.0 - pchan->stiffness[0]);
1170 weight[1] = (1.0 - pchan->stiffness[1]);
1171 weight[2] = (1.0 - pchan->stiffness[2]);
1172 switch (ikchan->jointType & ~IK_TRANSY) {
1175 if (!(ikchan->jointType & IK_TRANSY)) {
1177 ret = arm->addSegment(joint, parent, KDL::Joint::None, 0.0, tip);
1181 // RX only, get the X rotation
1183 ret = arm->addSegment(joint, parent, KDL::Joint::RotX, rot[0], tip);
1184 weights.push_back(weight[0]);
1187 // RY only, get the Y rotation
1189 ret = arm->addSegment(joint, parent, KDL::Joint::RotY, rot[0], tip);
1190 weights.push_back(weight[1]);
1193 // RZ only, get the Zz rotation
1195 ret = arm->addSegment(joint, parent, KDL::Joint::RotZ, rot[0], tip);
1196 weights.push_back(weight[2]);
1198 case IK_XDOF | IK_YDOF:
1200 ret = arm->addSegment(joint, parent, KDL::Joint::RotX, rot[0]);
1201 weights.push_back(weight[0]);
1206 ret = arm->addSegment(joint, parent, KDL::Joint::RotY, rot[1], tip);
1207 weights.push_back(weight[1]);
1212 ret = arm->addSegment(joint, parent, KDL::Joint::Swing, rot[0], tip);
1213 weights.push_back(weight[0]);
1214 weights.push_back(weight[2]);
1216 case IK_YDOF | IK_ZDOF:
1219 ret = arm->addSegment(joint, parent, KDL::Joint::RotZ, rot[0]);
1220 weights.push_back(weight[2]);
1225 ret = arm->addSegment(joint, parent, KDL::Joint::RotY, rot[1], tip);
1226 weights.push_back(weight[1]);
1229 case IK_SWING | IK_YDOF:
1230 // decompose in a Swing+RotY joint
1232 ret = arm->addSegment(joint, parent, KDL::Joint::Swing, rot[0]);
1233 weights.push_back(weight[0]);
1234 weights.push_back(weight[2]);
1239 ret = arm->addSegment(joint, parent, KDL::Joint::RotY, rot[2], tip);
1240 weights.push_back(weight[1]);
1245 ret = arm->addSegment(joint, parent, KDL::Joint::Sphere, rot[0], tip);
1246 weights.push_back(weight[0]);
1247 weights.push_back(weight[1]);
1248 weights.push_back(weight[2]);
1251 if (ret && (ikchan->jointType & IK_TRANSY)) {
1255 ret = arm->addSegment(joint, parent, KDL::Joint::TransY, rot[ikchan->ndof - 1]);
1256 const float ikstretch = pchan->ikstretch * pchan->ikstretch;
1257 /* why invert twice here? */
1258 weight[1] = (1.0 - minf(1.0 - ikstretch, 1.0f - 0.001f));
1259 weights.push_back(weight[1]);
1262 // error making the armature??
1264 // joint points to the segment that correspond to the bone per say
1265 ikchan->tail = joint;
1266 ikchan->head = parent;
1269 if ((ikchan->jointType & IK_XDOF) && (pchan->ikflag & (BONE_IK_XLIMIT | BONE_IK_ROTCTL))) {
1272 if (pchan->ikflag & BONE_IK_XLIMIT) {
1273 if (arm->addLimitConstraint(joint, 0, pchan->limitmin[0], pchan->limitmax[0]) < 0)
1276 if (pchan->ikflag & BONE_IK_ROTCTL) {
1277 if (arm->addConstraint(joint, joint_callback, ikchan, false, false) < 0)
1281 if ((ikchan->jointType & IK_YDOF) && (pchan->ikflag & (BONE_IK_YLIMIT | BONE_IK_ROTCTL))) {
1284 if (pchan->ikflag & BONE_IK_YLIMIT) {
1285 if (arm->addLimitConstraint(joint, 0, pchan->limitmin[1], pchan->limitmax[1]) < 0)
1288 if (pchan->ikflag & BONE_IK_ROTCTL) {
1289 if (arm->addConstraint(joint, joint_callback, ikchan, false, false) < 0)
1293 if ((ikchan->jointType & IK_ZDOF) && (pchan->ikflag & (BONE_IK_ZLIMIT | BONE_IK_ROTCTL))) {
1296 if (pchan->ikflag & BONE_IK_ZLIMIT) {
1297 if (arm->addLimitConstraint(joint, 0, pchan->limitmin[2], pchan->limitmax[2]) < 0)
1300 if (pchan->ikflag & BONE_IK_ROTCTL) {
1301 if (arm->addConstraint(joint, joint_callback, ikchan, false, false) < 0)
1305 if ((ikchan->jointType & IK_SWING) && (pchan->ikflag & (BONE_IK_XLIMIT | BONE_IK_ZLIMIT | BONE_IK_ROTCTL))) {
1308 if (pchan->ikflag & BONE_IK_XLIMIT) {
1309 if (arm->addLimitConstraint(joint, 0, pchan->limitmin[0], pchan->limitmax[0]) < 0)
1312 if (pchan->ikflag & BONE_IK_ZLIMIT) {
1313 if (arm->addLimitConstraint(joint, 1, pchan->limitmin[2], pchan->limitmax[2]) < 0)
1316 if (pchan->ikflag & BONE_IK_ROTCTL) {
1317 if (arm->addConstraint(joint, joint_callback, ikchan, false, false) < 0)
1321 if ((ikchan->jointType & IK_REVOLUTE) && (pchan->ikflag & BONE_IK_ROTCTL)) {
1324 if (arm->addConstraint(joint, joint_callback, ikchan, false, false) < 0)
1327 // no error, so restore
1329 rot += ikchan->ndof;
1335 // for each target, we need to add an end effector in the armature
1336 for (numtarget = 0, polarcon = NULL, ret = true, target = (PoseTarget *)tree->targets.first; target; target = (PoseTarget *)target->next) {
1337 condata = (bKinematicConstraint *)target->con->data;
1338 pchan = tree->pchan[target->tip];
1340 if (is_cartesian_constraint(target->con)) {
1341 // add the end effector
1342 IK_Target *iktarget = new IK_Target();
1343 ikscene->targets.push_back(iktarget);
1344 iktarget->ee = arm->addEndEffector(ikscene->channels[target->tip].tail);
1345 if (iktarget->ee == -1) {
1349 // initialize all the fields that we can set at this time
1350 iktarget->blenderConstraint = target->con;
1351 iktarget->channel = target->tip;
1352 iktarget->simulation = (ikparam->flag & ITASC_SIMULATION);
1353 iktarget->rootChannel = ikscene->channels[0].pchan;
1354 iktarget->owner = ob;
1355 iktarget->targetName = pchan->bone->name;
1356 iktarget->targetName += ":T:";
1357 iktarget->targetName += target->con->name;
1358 iktarget->constraintName = pchan->bone->name;
1359 iktarget->constraintName += ":C:";
1360 iktarget->constraintName += target->con->name;
1362 if (condata->poletar)
1363 // this constraint has a polar target
1364 polarcon = target->con;
1367 // deal with polar target if any
1368 if (numtarget == 1 && polarcon) {
1369 ikscene->polarConstraint = polarcon;
1371 // we can now add the armature
1372 // the armature is based on a moving frame.
1373 // initialize with the correct position in case there is no cache
1374 base_callback(iTaSC::Timestamp(), iTaSC::F_identity, initPose, ikscene);
1375 ikscene->base = new iTaSC::MovingFrame(initPose);
1376 ikscene->base->setCallback(base_callback, ikscene);
1377 std::string armname;
1378 armname = ob->id.name;
1380 ret = scene->addObject(armname, ikscene->base);
1381 armname = ob->id.name;
1384 ret = scene->addObject(armname, ikscene->armature, ikscene->base);
1390 e_matrix& Wq = arm->getWq();
1391 assert(Wq.cols() == (int)weights.size());
1392 for (int q = 0; q < Wq.cols(); q++)
1393 Wq(q, q) = weights[q];
1394 // get the inverse rest pose frame of the base to compute relative rest pose of end effectors
1395 // this is needed to handle the enforce parameter
1396 // ikscene->pchan[0] is the root channel of the tree
1397 // if it has no parent, then it's just the identify Frame
1398 float invBaseFrame[4][4];
1399 pchan = ikscene->channels[0].pchan;
1400 if (pchan->parent) {
1401 // it has a parent, get the pose matrix from it
1402 float baseFrame[4][4];
1403 pchan = pchan->parent;
1404 copy_m4_m4(baseFrame, pchan->bone->arm_mat);
1405 // move to the tail and scale to get rest pose of armature base
1406 copy_v3_v3(baseFrame[3], pchan->bone->arm_tail);
1407 invert_m4_m4(invBaseFrame, baseFrame);
1410 unit_m4(invBaseFrame);
1412 // finally add the constraint
1413 for (t = 0; t < ikscene->targets.size(); t++) {
1414 IK_Target *iktarget = ikscene->targets[t];
1415 iktarget->blscene = blscene;
1416 condata = (bKinematicConstraint *)iktarget->blenderConstraint->data;
1417 pchan = tree->pchan[iktarget->channel];
1418 unsigned int controltype, bonecnt;
1422 // add the end effector
1423 // estimate the average bone length, used to clamp feedback error
1424 for (bonecnt = 0, bonelen = 0.f, a = iktarget->channel; a >= 0; a = tree->parent[a], bonecnt++)
1425 bonelen += ikscene->blScale * tree->pchan[a]->bone->length;
1428 // store the rest pose of the end effector to compute enforce target
1429 copy_m4_m4(mat, pchan->bone->arm_mat);
1430 copy_v3_v3(mat[3], pchan->bone->arm_tail);
1431 // get the rest pose relative to the armature base
1432 mult_m4_m4m4(iktarget->eeRest, invBaseFrame, mat);
1433 iktarget->eeBlend = (!ikscene->polarConstraint && condata->type == CONSTRAINT_IK_COPYPOSE) ? true : false;
1434 // use target_callback to make sure the initPose includes enforce coefficient
1435 target_callback(iTaSC::Timestamp(), iTaSC::F_identity, initPose, iktarget);
1436 iktarget->target = new iTaSC::MovingFrame(initPose);
1437 iktarget->target->setCallback(target_callback, iktarget);
1438 ret = scene->addObject(iktarget->targetName, iktarget->target);
1442 switch (condata->type) {
1443 case CONSTRAINT_IK_COPYPOSE:
1445 if (condata->flag & CONSTRAINT_IK_ROT) {
1446 if (!(condata->flag & CONSTRAINT_IK_NO_ROT_X))
1447 controltype |= iTaSC::CopyPose::CTL_ROTATIONX;
1448 if (!(condata->flag & CONSTRAINT_IK_NO_ROT_Y))
1449 controltype |= iTaSC::CopyPose::CTL_ROTATIONY;
1450 if (!(condata->flag & CONSTRAINT_IK_NO_ROT_Z))
1451 controltype |= iTaSC::CopyPose::CTL_ROTATIONZ;
1453 if (condata->flag & CONSTRAINT_IK_POS) {
1454 if (!(condata->flag & CONSTRAINT_IK_NO_POS_X))
1455 controltype |= iTaSC::CopyPose::CTL_POSITIONX;
1456 if (!(condata->flag & CONSTRAINT_IK_NO_POS_Y))
1457 controltype |= iTaSC::CopyPose::CTL_POSITIONY;
1458 if (!(condata->flag & CONSTRAINT_IK_NO_POS_Z))
1459 controltype |= iTaSC::CopyPose::CTL_POSITIONZ;
1462 iktarget->constraint = new iTaSC::CopyPose(controltype, controltype, bonelen);
1464 if (controltype & iTaSC::CopyPose::CTL_POSITION)
1465 iktarget->constraint->setControlParameter(iTaSC::CopyPose::ID_POSITION, iTaSC::ACT_ALPHA, condata->weight);
1466 if (controltype & iTaSC::CopyPose::CTL_ROTATION)
1467 iktarget->constraint->setControlParameter(iTaSC::CopyPose::ID_ROTATION, iTaSC::ACT_ALPHA, condata->orientweight);
1468 iktarget->constraint->registerCallback(copypose_callback, iktarget);
1469 iktarget->errorCallback = copypose_error;
1470 iktarget->controlType = controltype;
1471 // add the constraint
1472 if (condata->flag & CONSTRAINT_IK_TARGETAXIS)
1473 ret = scene->addConstraintSet(iktarget->constraintName, iktarget->constraint, iktarget->targetName, armname, "", ikscene->channels[iktarget->channel].tail);
1475 ret = scene->addConstraintSet(iktarget->constraintName, iktarget->constraint, armname, iktarget->targetName, ikscene->channels[iktarget->channel].tail);
1478 case CONSTRAINT_IK_DISTANCE:
1479 iktarget->constraint = new iTaSC::Distance(bonelen);
1480 iktarget->constraint->setControlParameter(iTaSC::Distance::ID_DISTANCE, iTaSC::ACT_VALUE, condata->dist);
1481 iktarget->constraint->registerCallback(distance_callback, iktarget);
1482 iktarget->errorCallback = distance_error;
1483 // we can update the weight on each substep
1484 iktarget->constraint->substep(true);
1485 // add the constraint
1486 ret = scene->addConstraintSet(iktarget->constraintName, iktarget->constraint, armname, iktarget->targetName, ikscene->channels[iktarget->channel].tail);
1493 !scene->addCache(ikscene->cache) ||
1494 !scene->addSolver(ikscene->solver) ||
1495 !scene->initialize()) {
1502 static void create_scene(Scene *scene, Object *ob)
1504 bPoseChannel *pchan;
1506 // create the IK scene
1507 for (pchan = (bPoseChannel *)ob->pose->chanbase.first; pchan; pchan = (bPoseChannel *)pchan->next) {
1508 // by construction there is only one tree
1509 PoseTree *tree = (PoseTree *)pchan->iktree.first;
1511 IK_Data *ikdata = get_ikdata(ob->pose);
1512 // convert tree in iTaSC::Scene
1513 IK_Scene *ikscene = convert_tree(scene, ob, pchan);
1515 ikscene->next = ikdata->first;
1516 ikdata->first = ikscene;
1518 // delete the trees once we are done
1520 BLI_remlink(&pchan->iktree, tree);
1521 BLI_freelistN(&tree->targets);
1522 if (tree->pchan) MEM_freeN(tree->pchan);
1523 if (tree->parent) MEM_freeN(tree->parent);
1524 if (tree->basis_change) MEM_freeN(tree->basis_change);
1526 tree = (PoseTree *)pchan->iktree.first;
1532 /* returns 1 if scaling has changed and tree must be reinitialized */
1533 static int init_scene(Object *ob)
1535 // check also if scaling has changed
1536 float scale = len_v3(ob->obmat[1]);
1539 if (ob->pose->ikdata) {
1540 for (scene = ((IK_Data *)ob->pose->ikdata)->first;
1542 scene = scene->next) {
1543 if (fabs(scene->blScale - scale) > KDL::epsilon)
1545 scene->channels[0].pchan->flag |= POSE_IKTREE;
1551 static void execute_scene(Scene *blscene, IK_Scene *ikscene, bItasc *ikparam, float ctime, float frtime)
1555 if (ikparam->flag & ITASC_SIMULATION) {
1556 for (i = 0, ikchan = ikscene->channels; i < ikscene->numchan; i++, ++ikchan) {
1557 // In simulation mode we don't allow external contraint to change our bones, mark the channel done
1558 // also tell Blender that this channel is part of IK tree (cleared on each BKE_pose_where_is()
1559 ikchan->pchan->flag |= (POSE_DONE | POSE_CHAIN);
1560 ikchan->jointValid = 0;
1564 // in animation mode, we must get the bone position from action and constraints
1565 for (i = 0, ikchan = ikscene->channels; i < ikscene->numchan; i++, ++ikchan) {
1566 if (!(ikchan->pchan->flag & POSE_DONE))
1567 BKE_pose_where_is_bone(blscene, ikscene->blArmature, ikchan->pchan, ctime, 1);
1568 // tell blender that this channel was controlled by IK, it's cleared on each BKE_pose_where_is()
1569 ikchan->pchan->flag |= (POSE_DONE | POSE_CHAIN);
1570 ikchan->jointValid = 0;
1573 // only run execute the scene if at least one of our target is enabled
1574 for (i = ikscene->targets.size(); i > 0; --i) {
1575 IK_Target *iktarget = ikscene->targets[i - 1];
1576 if (!(iktarget->blenderConstraint->flag & CONSTRAINT_OFF))
1579 if (i == 0 && ikscene->armature->getNrOfConstraints() == 0)
1580 // all constraint disabled
1584 double timestamp = ctime * frtime + 2147483.648;
1585 double timestep = frtime;
1586 bool reiterate = (ikparam->flag & ITASC_REITERATION) ? true : false;
1587 int numstep = (ikparam->flag & ITASC_AUTO_STEP) ? 0 : ikparam->numstep;
1588 bool simulation = true;
1590 if (ikparam->flag & ITASC_SIMULATION) {
1591 ikscene->solver->setParam(iTaSC::Solver::DLS_QMAX, ikparam->maxvel);
1594 // in animation mode we start from the pose after action and constraint
1595 convert_pose(ikscene);
1596 ikscene->armature->setJointArray(ikscene->jointArray);
1597 // and we don't handle velocity
1600 // time is virtual, so take fixed value for velocity parameters (see itasc_update_param)
1601 // and choose 1s timestep to allow having velocity parameters in radiant
1603 // use auto setup to let the solver test the variation of the joints
1607 if (ikscene->cache && !reiterate && simulation) {
1608 iTaSC::CacheTS sts, cts;
1609 sts = cts = (iTaSC::CacheTS)(timestamp * 1000.0 + 0.5);
1610 if (ikscene->cache->getPreviousCacheItem(ikscene->armature, 0, &cts) == NULL || cts == 0) {
1611 // the cache is empty before this time, reiterate
1612 if (ikparam->flag & ITASC_INITIAL_REITERATION)
1616 // can take the cache as a start point.
1618 timestep = sts / 1000.0;
1621 // don't cache if we are reiterating because we don't want to destroy the cache unnecessarily
1622 ikscene->scene->update(timestamp, timestep, numstep, false, !reiterate, simulation);
1624 // how many times do we reiterate?
1625 for (i = 0; i < ikparam->numiter; i++) {
1626 if (ikscene->armature->getMaxJointChange() < ikparam->precision ||
1627 ikscene->armature->getMaxEndEffectorChange() < ikparam->precision)
1631 ikscene->scene->update(timestamp, timestep, numstep, true, false, simulation);
1634 // one more fake iteration to cache
1635 ikscene->scene->update(timestamp, 0.0, 1, true, true, true);
1638 // compute constraint error
1639 for (i = ikscene->targets.size(); i > 0; --i) {
1640 IK_Target *iktarget = ikscene->targets[i - 1];
1641 if (!(iktarget->blenderConstraint->flag & CONSTRAINT_OFF)) {
1642 unsigned int nvalues;
1643 const iTaSC::ConstraintValues *values;
1644 values = iktarget->constraint->getControlParameters(&nvalues);
1645 iktarget->errorCallback(values, nvalues, iktarget);
1648 // Apply result to bone:
1649 // walk the ikscene->channels
1650 // for each, get the Frame of the joint corresponding to the bone relative to its parent
1651 // combine the parent and the joint frame to get the frame relative to armature
1652 // a backward translation of the bone length gives the head
1653 // if TY, compute the scale as the ratio of the joint length with rest pose length
1654 iTaSC::Armature *arm = ikscene->armature;
1656 double q_rest[3], q[3];
1657 const KDL::Joint *joint;
1658 const KDL::Frame *tip;
1659 bPoseChannel *pchan;
1663 for (i = 0, ikchan = ikscene->channels; i < ikscene->numchan; ++i, ++ikchan) {
1665 if (!arm->getRelativeFrame(frame, ikchan->tail))
1667 // this frame is relative to base, make it relative to object
1668 ikchan->frame = ikscene->baseFrame * frame;
1671 if (!arm->getRelativeFrame(frame, ikchan->tail, ikscene->channels[ikchan->parent].tail))
1673 // combine with parent frame to get frame relative to object
1674 ikchan->frame = ikscene->channels[ikchan->parent].frame * frame;
1676 // ikchan->frame is the tail frame relative to object
1678 if (!arm->getSegment(ikchan->tail, 3, joint, q_rest[0], q[0], tip))
1680 if (joint->getType() == KDL::Joint::TransY) {
1681 // stretch bones have a TY joint, compute the scale
1682 scale = (float)(q[0] / q_rest[0]);
1683 // the length is the joint itself
1684 length = (float)q[0];
1688 // for fixed bone, the length is in the tip (always along Y axis)
1691 // ready to compute the pose mat
1692 pchan = ikchan->pchan;
1694 ikchan->frame.getValue(&pchan->pose_mat[0][0]);
1695 // the scale of the object was included in the ik scene, take it out now
1696 // because the pose channels are relative to the object
1697 mul_v3_fl(pchan->pose_mat[3], ikscene->blInvScale);
1698 length *= ikscene->blInvScale;
1699 copy_v3_v3(pchan->pose_tail, pchan->pose_mat[3]);
1701 copy_v3_v3(yaxis, pchan->pose_mat[1]);
1702 mul_v3_fl(yaxis, length);
1703 sub_v3_v3v3(pchan->pose_mat[3], pchan->pose_mat[3], yaxis);
1704 copy_v3_v3(pchan->pose_head, pchan->pose_mat[3]);
1706 mul_v3_fl(pchan->pose_mat[0], scale);
1707 mul_v3_fl(pchan->pose_mat[1], scale);
1708 mul_v3_fl(pchan->pose_mat[2], scale);
1710 if (i < ikscene->numchan) {
1716 //---------------------------------------------------
1719 void itasc_initialize_tree(struct Scene *scene, Object *ob, float ctime)
1721 bPoseChannel *pchan;
1724 if (ob->pose->ikdata != NULL && !(ob->pose->flag & POSE_WAS_REBUILT)) {
1725 if (!init_scene(ob))
1728 // first remove old scene
1729 itasc_clear_data(ob->pose);
1730 // we should handle all the constraint and mark them all disabled
1731 // for blender but we'll start with the IK constraint alone
1732 for (pchan = (bPoseChannel *)ob->pose->chanbase.first; pchan; pchan = (bPoseChannel *)pchan->next) {
1733 if (pchan->constflag & PCHAN_HAS_IK)
1734 count += initialize_scene(ob, pchan);
1736 // if at least one tree, create the scenes from the PoseTree stored in the channels
1738 create_scene(scene, ob);
1739 itasc_update_param(ob->pose);
1740 // make sure we don't rebuilt until the user changes something important
1741 ob->pose->flag &= ~POSE_WAS_REBUILT;
1744 void itasc_execute_tree(struct Scene *scene, struct Object *ob, struct bPoseChannel *pchan, float ctime)
1746 if (ob->pose->ikdata) {
1747 IK_Data *ikdata = (IK_Data *)ob->pose->ikdata;
1748 bItasc *ikparam = (bItasc *) ob->pose->ikparam;
1749 // we need default parameters
1750 if (!ikparam) ikparam = &DefIKParam;
1752 for (IK_Scene *ikscene = ikdata->first; ikscene; ikscene = ikscene->next) {
1753 if (ikscene->channels[0].pchan == pchan) {
1754 float timestep = scene->r.frs_sec_base / scene->r.frs_sec;
1755 if (ob->pose->flag & POSE_GAME_ENGINE) {
1756 timestep = ob->pose->ctime;
1757 // limit the timestep to avoid excessive number of iteration
1758 if (timestep > 0.2f)
1761 execute_scene(scene, ikscene, ikparam, ctime, timestep);
1768 void itasc_release_tree(struct Scene *scene, struct Object *ob, float ctime)
1770 // not used for iTaSC
1773 void itasc_clear_data(struct bPose *pose)
1776 IK_Data *ikdata = (IK_Data *)pose->ikdata;
1777 for (IK_Scene *scene = ikdata->first; scene; scene = ikdata->first) {
1778 ikdata->first = scene->next;
1782 pose->ikdata = NULL;
1786 void itasc_clear_cache(struct bPose *pose)
1789 IK_Data *ikdata = (IK_Data *)pose->ikdata;
1790 for (IK_Scene *scene = ikdata->first; scene; scene = scene->next) {
1792 // clear all cache but leaving the timestamp 0 (=rest pose)
1793 scene->cache->clearCacheFrom(NULL, 1);
1798 void itasc_update_param(struct bPose *pose)
1800 if (pose->ikdata && pose->ikparam) {
1801 IK_Data *ikdata = (IK_Data *)pose->ikdata;
1802 bItasc *ikparam = (bItasc *)pose->ikparam;
1803 for (IK_Scene *ikscene = ikdata->first; ikscene; ikscene = ikscene->next) {
1804 double armlength = ikscene->armature->getArmLength();
1805 ikscene->solver->setParam(iTaSC::Solver::DLS_LAMBDA_MAX, ikparam->dampmax * armlength);
1806 ikscene->solver->setParam(iTaSC::Solver::DLS_EPSILON, ikparam->dampeps * armlength);
1807 if (ikparam->flag & ITASC_SIMULATION) {
1808 ikscene->scene->setParam(iTaSC::Scene::MIN_TIMESTEP, ikparam->minstep);
1809 ikscene->scene->setParam(iTaSC::Scene::MAX_TIMESTEP, ikparam->maxstep);
1810 ikscene->solver->setParam(iTaSC::Solver::DLS_QMAX, ikparam->maxvel);
1811 ikscene->armature->setControlParameter(CONSTRAINT_ID_ALL, iTaSC::Armature::ID_JOINT, iTaSC::ACT_FEEDBACK, ikparam->feedback);
1814 // in animation mode timestep is 1s by convention =>
1815 // qmax becomes radiant and feedback becomes fraction of error gap corrected in one iteration
1816 ikscene->scene->setParam(iTaSC::Scene::MIN_TIMESTEP, 1.0);
1817 ikscene->scene->setParam(iTaSC::Scene::MAX_TIMESTEP, 1.0);
1818 ikscene->solver->setParam(iTaSC::Solver::DLS_QMAX, 0.52);
1819 ikscene->armature->setControlParameter(CONSTRAINT_ID_ALL, iTaSC::Armature::ID_JOINT, iTaSC::ACT_FEEDBACK, 0.8);
1825 void itasc_test_constraint(struct Object *ob, struct bConstraint *cons)
1827 struct bKinematicConstraint *data = (struct bKinematicConstraint *)cons->data;
1829 /* only for IK constraint */
1830 if (cons->type != CONSTRAINT_TYPE_KINEMATIC || data == NULL)
1833 switch (data->type) {
1834 case CONSTRAINT_IK_COPYPOSE:
1835 case CONSTRAINT_IK_DISTANCE:
1836 /* cartesian space constraint */