mirror of
https://github.com/overte-org/overte.git
synced 2025-08-10 03:40:20 +02:00
build local list of IK targets every frame
This commit is contained in:
parent
089c719612
commit
9a86fc2e62
3 changed files with 85 additions and 55 deletions
|
@ -55,7 +55,20 @@ void AnimInverseKinematics::computeAbsolutePoses(AnimPoseVec& absolutePoses) con
|
||||||
|
|
||||||
void AnimInverseKinematics::setTargetVars(const QString& jointName, const QString& positionVar, const QString& rotationVar) {
|
void AnimInverseKinematics::setTargetVars(const QString& jointName, const QString& positionVar, const QString& rotationVar) {
|
||||||
// if there are dups, last one wins.
|
// if there are dups, last one wins.
|
||||||
_targetVarVec.push_back(IKTargetVar(jointName, positionVar.toStdString(), rotationVar.toStdString()));
|
bool found = false;
|
||||||
|
for (auto& targetVar: _targetVarVec) {
|
||||||
|
if (targetVar.jointName == jointName) {
|
||||||
|
// update existing targetVar
|
||||||
|
targetVar.positionVar = positionVar.toStdString();
|
||||||
|
targetVar.rotationVar = rotationVar.toStdString();
|
||||||
|
found = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (!found) {
|
||||||
|
// create a new entry
|
||||||
|
_targetVarVec.push_back(IKTargetVar(jointName, positionVar.toStdString(), rotationVar.toStdString()));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static int findRootJointInSkeleton(AnimSkeleton::ConstPointer skeleton, int index) {
|
static int findRootJointInSkeleton(AnimSkeleton::ConstPointer skeleton, int index) {
|
||||||
|
@ -69,6 +82,12 @@ static int findRootJointInSkeleton(AnimSkeleton::ConstPointer skeleton, int inde
|
||||||
return rootIndex;
|
return rootIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
struct IKTarget {
|
||||||
|
AnimPose pose;
|
||||||
|
int index;
|
||||||
|
int rootIndex;
|
||||||
|
};
|
||||||
|
|
||||||
//virtual
|
//virtual
|
||||||
const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVars, float dt, AnimNode::Triggers& triggersOut) {
|
const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVars, float dt, AnimNode::Triggers& triggersOut) {
|
||||||
|
|
||||||
|
@ -77,40 +96,53 @@ const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVar
|
||||||
return _relativePoses;
|
return _relativePoses;
|
||||||
}
|
}
|
||||||
|
|
||||||
// evaluate target vars
|
// build a list of targets from _targetVarVec
|
||||||
|
std::vector<IKTarget> targets;
|
||||||
|
bool removeUnfoundJoints = false;
|
||||||
for (auto& targetVar : _targetVarVec) {
|
for (auto& targetVar : _targetVarVec) {
|
||||||
|
if (targetVar.jointIndex == -1) {
|
||||||
// lazy look up of jointIndices and insertion into _absoluteTargets map
|
// this targetVar hasn't been validated yet...
|
||||||
if (!targetVar.hasPerformedJointLookup) {
|
int jointIndex = _skeleton->nameToJointIndex(targetVar.jointName);
|
||||||
targetVar.jointIndex = _skeleton->nameToJointIndex(targetVar.jointName);
|
if (jointIndex >= 0) {
|
||||||
if (targetVar.jointIndex >= 0) {
|
// this targetVar has a valid joint --> cache the indices
|
||||||
// insert into _absoluteTargets map
|
targetVar.jointIndex = jointIndex;
|
||||||
IKTarget target;
|
targetVar.rootIndex = findRootJointInSkeleton(_skeleton, jointIndex);
|
||||||
target.pose = AnimPose::identity;
|
|
||||||
target.rootIndex = findRootJointInSkeleton(_skeleton, targetVar.jointIndex);
|
|
||||||
_absoluteTargets[targetVar.jointIndex] = target;
|
|
||||||
|
|
||||||
if (targetVar.jointIndex > _maxTargetIndex) {
|
|
||||||
_maxTargetIndex = targetVar.jointIndex;
|
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
qCWarning(animation) << "AnimInverseKinematics could not find jointName" << targetVar.jointName << "in skeleton";
|
qCWarning(animation) << "AnimInverseKinematics could not find jointName" << targetVar.jointName << "in skeleton";
|
||||||
|
removeUnfoundJoints = true;
|
||||||
}
|
}
|
||||||
targetVar.hasPerformedJointLookup = true;
|
} else {
|
||||||
}
|
// TODO: get this done without a double-lookup of each var in animVars
|
||||||
|
if (animVars.hasKey(targetVar.positionVar) || animVars.hasKey(targetVar.rotationVar)) {
|
||||||
if (targetVar.jointIndex >= 0) {
|
IKTarget target;
|
||||||
// update pose in _absoluteTargets map
|
|
||||||
auto iter = _absoluteTargets.find(targetVar.jointIndex);
|
|
||||||
if (iter != _absoluteTargets.end()) {
|
|
||||||
AnimPose defaultPose = _skeleton->getAbsolutePose(targetVar.jointIndex, _relativePoses);
|
AnimPose defaultPose = _skeleton->getAbsolutePose(targetVar.jointIndex, _relativePoses);
|
||||||
iter->second.pose.trans = animVars.lookup(targetVar.positionVar, defaultPose.trans);
|
target.pose.trans = animVars.lookup(targetVar.positionVar, defaultPose.trans);
|
||||||
iter->second.pose.rot = animVars.lookup(targetVar.rotationVar, defaultPose.rot);
|
target.pose.rot = animVars.lookup(targetVar.rotationVar, defaultPose.rot);
|
||||||
|
target.rootIndex = targetVar.rootIndex;
|
||||||
|
target.index = targetVar.jointIndex;
|
||||||
|
targets.push_back(target);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_absoluteTargets.empty()) {
|
if (removeUnfoundJoints) {
|
||||||
|
int numVars = _targetVarVec.size();
|
||||||
|
int i = 0;
|
||||||
|
while (i < numVars) {
|
||||||
|
if (_targetVarVec[i].jointIndex == -1) {
|
||||||
|
if (numVars > 1) {
|
||||||
|
// swap i for last element
|
||||||
|
_targetVarVec[i] = _targetVarVec[numVars - 1];
|
||||||
|
}
|
||||||
|
_targetVarVec.pop_back();
|
||||||
|
--numVars;
|
||||||
|
} else {
|
||||||
|
++i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (targets.empty()) {
|
||||||
// no IK targets but still need to enforce constraints
|
// no IK targets but still need to enforce constraints
|
||||||
std::map<int, RotationConstraint*>::iterator constraintItr = _constraints.begin();
|
std::map<int, RotationConstraint*>::iterator constraintItr = _constraints.begin();
|
||||||
while (constraintItr != _constraints.end()) {
|
while (constraintItr != _constraints.end()) {
|
||||||
|
@ -133,11 +165,11 @@ const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVar
|
||||||
quint64 expiry = usecTimestampNow() + MAX_IK_TIME;
|
quint64 expiry = usecTimestampNow() + MAX_IK_TIME;
|
||||||
do {
|
do {
|
||||||
largestError = 0.0f;
|
largestError = 0.0f;
|
||||||
for (auto& targetPair: _absoluteTargets) {
|
for (auto& target: targets) {
|
||||||
int lowestMovedIndex = _relativePoses.size() - 1;
|
int lowestMovedIndex = _relativePoses.size() - 1;
|
||||||
int tipIndex = targetPair.first;
|
int tipIndex = target.index;
|
||||||
AnimPose targetPose = targetPair.second.pose;
|
AnimPose targetPose = target.pose;
|
||||||
int rootIndex = targetPair.second.rootIndex;
|
int rootIndex = target.rootIndex;
|
||||||
if (rootIndex != -1) {
|
if (rootIndex != -1) {
|
||||||
// transform targetPose into skeleton's absolute frame
|
// transform targetPose into skeleton's absolute frame
|
||||||
AnimPose& rootPose = _relativePoses[rootIndex];
|
AnimPose& rootPose = _relativePoses[rootIndex];
|
||||||
|
@ -148,11 +180,11 @@ const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVar
|
||||||
glm::vec3 tip = absolutePoses[tipIndex].trans;
|
glm::vec3 tip = absolutePoses[tipIndex].trans;
|
||||||
float error = glm::length(targetPose.trans - tip);
|
float error = glm::length(targetPose.trans - tip);
|
||||||
|
|
||||||
// descend toward root, rotating each joint to get tip closer to target
|
// descend toward root, pivoting each joint to get tip closer to target
|
||||||
int index = _skeleton->getParentIndex(tipIndex);
|
int pivotIndex = _skeleton->getParentIndex(tipIndex);
|
||||||
while (index != -1 && error > ACCEPTABLE_RELATIVE_ERROR) {
|
while (pivotIndex != -1 && error > ACCEPTABLE_RELATIVE_ERROR) {
|
||||||
// compute the two lines that should be aligned
|
// compute the two lines that should be aligned
|
||||||
glm::vec3 jointPosition = absolutePoses[index].trans;
|
glm::vec3 jointPosition = absolutePoses[pivotIndex].trans;
|
||||||
glm::vec3 leverArm = tip - jointPosition;
|
glm::vec3 leverArm = tip - jointPosition;
|
||||||
glm::vec3 targetLine = targetPose.trans - jointPosition;
|
glm::vec3 targetLine = targetPose.trans - jointPosition;
|
||||||
|
|
||||||
|
@ -171,29 +203,34 @@ const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVar
|
||||||
angle = 0.5f * angle;
|
angle = 0.5f * angle;
|
||||||
glm::quat deltaRotation = glm::angleAxis(angle, axis);
|
glm::quat deltaRotation = glm::angleAxis(angle, axis);
|
||||||
|
|
||||||
int parentIndex = _skeleton->getParentIndex(index);
|
int parentIndex = _skeleton->getParentIndex(pivotIndex);
|
||||||
if (parentIndex == -1) {
|
if (parentIndex == -1) {
|
||||||
// TODO? apply constraints to root?
|
// TODO? apply constraints to root?
|
||||||
// TODO? harvest the root's transform as movement of entire skeleton?
|
// TODO? harvest the root's transform as movement of entire skeleton?
|
||||||
} else {
|
} else {
|
||||||
// compute joint's new parent-relative rotation
|
// compute joint's new parent-relative rotation
|
||||||
// Q' = dQ * Q and Q = Qp * q --> q' = Qp^ * dQ * Q
|
// Q' = dQ * Q and Q = Qp * q --> q' = Qp^ * dQ * Q
|
||||||
glm::quat newRot = glm::normalize(glm::inverse(absolutePoses[parentIndex].rot) * deltaRotation * absolutePoses[index].rot);
|
glm::quat newRot = glm::normalize(glm::inverse(
|
||||||
RotationConstraint* constraint = getConstraint(index);
|
absolutePoses[parentIndex].rot) *
|
||||||
|
deltaRotation *
|
||||||
|
absolutePoses[pivotIndex].rot);
|
||||||
|
RotationConstraint* constraint = getConstraint(pivotIndex);
|
||||||
if (constraint) {
|
if (constraint) {
|
||||||
bool constrained = constraint->apply(newRot);
|
bool constrained = constraint->apply(newRot);
|
||||||
if (constrained) {
|
if (constrained) {
|
||||||
// the constraint will modify the movement of the tip so we have to compute the modified
|
// the constraint will modify the movement of the tip so we have to compute the modified
|
||||||
// model-frame deltaRotation
|
// model-frame deltaRotation
|
||||||
// Q' = Qp^ * dQ * Q --> dQ = Qp * Q' * Q^
|
// Q' = Qp^ * dQ * Q --> dQ = Qp * Q' * Q^
|
||||||
deltaRotation = absolutePoses[parentIndex].rot * newRot * glm::inverse(absolutePoses[index].rot);
|
deltaRotation = absolutePoses[parentIndex].rot *
|
||||||
|
newRot *
|
||||||
|
glm::inverse(absolutePoses[pivotIndex].rot);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
_relativePoses[index].rot = newRot;
|
_relativePoses[pivotIndex].rot = newRot;
|
||||||
}
|
}
|
||||||
// this joint has been changed so we check to see if it has the lowest index
|
// this joint has been changed so we check to see if it has the lowest index
|
||||||
if (index < lowestMovedIndex) {
|
if (pivotIndex < lowestMovedIndex) {
|
||||||
lowestMovedIndex = index;
|
lowestMovedIndex = pivotIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
// keep track of tip's new position as we descend towards root
|
// keep track of tip's new position as we descend towards root
|
||||||
|
@ -201,7 +238,7 @@ const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVar
|
||||||
error = glm::length(targetPose.trans - tip);
|
error = glm::length(targetPose.trans - tip);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
index = _skeleton->getParentIndex(index);
|
pivotIndex = _skeleton->getParentIndex(pivotIndex);
|
||||||
}
|
}
|
||||||
if (largestError < error) {
|
if (largestError < error) {
|
||||||
largestError = error;
|
largestError = error;
|
||||||
|
@ -581,13 +618,10 @@ void AnimInverseKinematics::setSkeletonInternal(AnimSkeleton::ConstPointer skele
|
||||||
AnimNode::setSkeletonInternal(skeleton);
|
AnimNode::setSkeletonInternal(skeleton);
|
||||||
|
|
||||||
// invalidate all targetVars
|
// invalidate all targetVars
|
||||||
for (auto& targetVar : _targetVarVec) {
|
for (auto& targetVar: _targetVarVec) {
|
||||||
targetVar.hasPerformedJointLookup = false;
|
targetVar.jointIndex = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
// invalidate all targets
|
|
||||||
_absoluteTargets.clear();
|
|
||||||
|
|
||||||
_maxTargetIndex = 0;
|
_maxTargetIndex = 0;
|
||||||
|
|
||||||
if (skeleton) {
|
if (skeleton) {
|
||||||
|
|
|
@ -50,23 +50,17 @@ protected:
|
||||||
rotationVar(rotationVarIn),
|
rotationVar(rotationVarIn),
|
||||||
jointName(jointNameIn),
|
jointName(jointNameIn),
|
||||||
jointIndex(-1),
|
jointIndex(-1),
|
||||||
hasPerformedJointLookup(false) {}
|
rootIndex(-1) {}
|
||||||
|
|
||||||
std::string positionVar;
|
std::string positionVar;
|
||||||
std::string rotationVar;
|
std::string rotationVar;
|
||||||
QString jointName;
|
QString jointName;
|
||||||
int jointIndex; // cached joint index
|
int jointIndex; // cached joint index
|
||||||
bool hasPerformedJointLookup = false;
|
int rootIndex; // cached root index
|
||||||
};
|
|
||||||
|
|
||||||
struct IKTarget {
|
|
||||||
AnimPose pose;
|
|
||||||
int rootIndex;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
std::map<int, RotationConstraint*> _constraints;
|
std::map<int, RotationConstraint*> _constraints;
|
||||||
std::vector<IKTargetVar> _targetVarVec;
|
std::vector<IKTargetVar> _targetVarVec;
|
||||||
std::map<int, IKTarget> _absoluteTargets; // IK targets of end-points
|
|
||||||
AnimPoseVec _defaultRelativePoses; // poses of the relaxed state
|
AnimPoseVec _defaultRelativePoses; // poses of the relaxed state
|
||||||
AnimPoseVec _relativePoses; // current relative poses
|
AnimPoseVec _relativePoses; // current relative poses
|
||||||
|
|
||||||
|
|
|
@ -154,6 +154,8 @@ public:
|
||||||
void setTrigger(const std::string& key) { _triggers.insert(key); }
|
void setTrigger(const std::string& key) { _triggers.insert(key); }
|
||||||
void clearTriggers() { _triggers.clear(); }
|
void clearTriggers() { _triggers.clear(); }
|
||||||
|
|
||||||
|
bool hasKey(const std::string& key) const { return _map.find(key) != _map.end(); }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
std::map<std::string, AnimVariant> _map;
|
std::map<std::string, AnimVariant> _map;
|
||||||
std::set<std::string> _triggers;
|
std::set<std::string> _triggers;
|
||||||
|
|
Loading…
Reference in a new issue