Seed AnimGraph with hand controller position and orientation.

This commit is contained in:
Anthony J. Thibault 2015-09-09 18:16:57 -07:00
parent ad49d0dd59
commit 09b2d8e4a4
3 changed files with 13 additions and 74 deletions

View file

@ -68,62 +68,6 @@ static int findRootJointInSkeleton(AnimSkeleton::ConstPointer skeleton, int inde
return rootIndex;
}
/*
void AnimInverseKinematics::updateTarget(int index, const glm::vec3& position, const glm::quat& rotation) {
std::map<int, IKTarget>::iterator targetItr = _absoluteTargets.find(index);
if (targetItr != _absoluteTargets.end()) {
// update existing target
targetItr->second.pose.rot = rotation;
targetItr->second.pose.trans = position;
} else {
// add new target
assert(index >= 0 && index < _skeleton->getNumJoints());
IKTarget target;
target.pose = AnimPose(glm::vec3(1.0f), rotation, position);
// walk down the skeleton hierarchy to find the joint's root
int rootIndex = -1;
int parentIndex = _skeleton->getParentIndex(index);
while (parentIndex != -1) {
rootIndex = parentIndex;
parentIndex = _skeleton->getParentIndex(parentIndex);
}
target.rootIndex = rootIndex;
_absoluteTargets[index] = target;
if (index > _maxTargetIndex) {
_maxTargetIndex = index;
}
}
}
void AnimInverseKinematics::updateTarget(const QString& name, const glm::vec3& position, const glm::quat& rotation) {
int index = _skeleton->nameToJointIndex(name);
if (index != -1) {
updateTarget(index, position, rotation);
}
}
void AnimInverseKinematics::clearTarget(int index) {
_absoluteTargets.erase(index);
// recompute _maxTargetIndex
_maxTargetIndex = 0;
for (auto& targetPair: _absoluteTargets) {
int targetIndex = targetPair.first;
if (targetIndex < _maxTargetIndex) {
_maxTargetIndex = targetIndex;
}
}
}
void AnimInverseKinematics::clearAllTargets() {
_absoluteTargets.clear();
_maxTargetIndex = 0;
}
*/
//virtual
const AnimPoseVec& AnimInverseKinematics::evaluate(const AnimVariantMap& animVars, float dt, AnimNode::Triggers& triggersOut) {

View file

@ -29,21 +29,6 @@ public:
void setTargetVars(const QString& jointName, const QString& positionVar, const QString& rotationVar);
/*
/// \param index index of end effector
/// \param position target position in the frame of the end-effector's root (not the parent!)
/// \param rotation target rotation in the frame of the end-effector's root (not the parent!)
void updateTarget(int index, const glm::vec3& position, const glm::quat& rotation);
/// \param name name of end effector
/// \param position target position in the frame of the end-effector's root (not the parent!)
/// \param rotation target rotation in the frame of the end-effector's root (not the parent!)
void updateTarget(const QString& name, const glm::vec3& position, const glm::quat& rotation);
void clearTarget(int index);
void clearAllTargets();
*/
virtual const AnimPoseVec& evaluate(const AnimVariantMap& animVars, float dt, AnimNode::Triggers& triggersOut) override;
virtual const AnimPoseVec& overlay(const AnimVariantMap& animVars, float dt, Triggers& triggersOut, const AnimPoseVec& underPoses) override;

View file

@ -444,9 +444,6 @@ void Rig::computeMotionAnimationState(float deltaTime, const glm::vec3& worldPos
static float t = 0.0f;
_animVars.set("sine", static_cast<float>(0.5 * sin(t) + 0.5));
_animVars.set("rightHandPosition", glm::vec3(0.5f * cos(t), 0.5f * sin(t) + 1.5f, 1.0f));
_animVars.set("leftHandPosition", glm::vec3(0.5f * cos(-t + 3.1415f), 0.5f * sin(-t + 3.1415f) + 1.5f, 1.0f));
// default anim vars to notMoving and notTurning
_animVars.set("isMovingForward", false);
_animVars.set("isMovingBackward", false);
@ -740,6 +737,19 @@ void Rig::inverseKinematics(int endIndex, glm::vec3 targetPosition, const glm::q
}
int numFree = freeLineage.size();
if (_enableAnimGraph && _animSkeleton) {
if (endIndex == _leftHandJointIndex) {
auto rootTrans = _animSkeleton->getAbsoluteBindPose(_rootJointIndex).trans;
_animVars.set("leftHandPosition", targetPosition + rootTrans);
_animVars.set("leftHandRotation", targetRotation);
} else if (endIndex == _rightHandJointIndex) {
auto rootTrans = _animSkeleton->getAbsoluteBindPose(_rootJointIndex).trans;
_animVars.set("rightHandPosition", targetPosition + rootTrans);
_animVars.set("rightHandRotation", targetRotation);
}
return;
}
// store and remember topmost parent transform
glm::mat4 topParentTransform;
{