mirror of
https://github.com/overte-org/overte.git
synced 2025-08-18 04:37:17 +02:00
Isolate JointStates within the Rig class
Except for SkeletalModel::computeBounds() JointStates are now completly encapsulated by the Rig. Now we can start using AnimPoses instead and in parallel with the JointState implementation. Then we can assert that they are identical, before removing JointStates. This check in has many comments with the AJT tag. Each one of these cases will need to be revisitied and fixed. In particular // AJT: LEGACY will be used to enclose all code in the Rig which manipulates the _jointState QVector.
This commit is contained in:
parent
11440f92f4
commit
e698d3c1e8
11 changed files with 140 additions and 276 deletions
|
@ -1354,7 +1354,7 @@ void MyAvatar::initAnimGraph() {
|
|||
auto graphUrl = QUrl(_animGraphUrl.isEmpty() ?
|
||||
QUrl::fromLocalFile(PathUtils::resourcesPath() + "meshes/defaultAvatar_full/avatar-animation.json") :
|
||||
_animGraphUrl);
|
||||
_rig->initAnimGraph(graphUrl, _skeletonModel.getGeometry()->getFBXGeometry());
|
||||
_rig->initAnimGraph(graphUrl);
|
||||
}
|
||||
|
||||
void MyAvatar::destroyAnimGraph() {
|
||||
|
|
|
@ -40,9 +40,9 @@ SkeletonModel::SkeletonModel(Avatar* owningAvatar, QObject* parent, RigPointer r
|
|||
SkeletonModel::~SkeletonModel() {
|
||||
}
|
||||
|
||||
void SkeletonModel::initJointStates(QVector<JointState> states) {
|
||||
void SkeletonModel::initJointStates() {
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
glm::mat4 rootTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
glm::mat4 modelOffset = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
|
||||
int rootJointIndex = geometry.rootJointIndex;
|
||||
int leftHandJointIndex = geometry.leftHandJointIndex;
|
||||
|
@ -52,7 +52,7 @@ void SkeletonModel::initJointStates(QVector<JointState> states) {
|
|||
int rightElbowJointIndex = rightHandJointIndex >= 0 ? geometry.joints.at(rightHandJointIndex).parentIndex : -1;
|
||||
int rightShoulderJointIndex = rightElbowJointIndex >= 0 ? geometry.joints.at(rightElbowJointIndex).parentIndex : -1;
|
||||
|
||||
_rig->initJointStates(states, rootTransform,
|
||||
_rig->initJointStates(geometry, modelOffset,
|
||||
rootJointIndex,
|
||||
leftHandJointIndex,
|
||||
leftElbowJointIndex,
|
||||
|
@ -80,12 +80,14 @@ void SkeletonModel::initJointStates(QVector<JointState> states) {
|
|||
_defaultEyeModelPosition = _defaultEyeModelPosition / _scale;
|
||||
}
|
||||
|
||||
/* AJT: DISABLED, only need this to compute bounding shape!
|
||||
// the SkeletonModel override of updateJointState() will clear the translation part
|
||||
// of its root joint and we need that done before we try to build shapes hence we
|
||||
// recompute all joint transforms at this time.
|
||||
for (int i = 0; i < _rig->getJointStateCount(); i++) {
|
||||
_rig->updateJointState(i, rootTransform);
|
||||
}
|
||||
*/
|
||||
|
||||
computeBoundingShape();
|
||||
|
||||
|
@ -184,10 +186,11 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
|
|||
|
||||
_rig->updateFromEyeParameters(eyeParams);
|
||||
|
||||
/* AJT: FIXME this will likely break eye tracking...
|
||||
// rebuild the jointState transform for the eyes only. Must be after updateRig.
|
||||
_rig->updateJointState(eyeParams.leftEyeJointIndex, parentTransform);
|
||||
_rig->updateJointState(eyeParams.rightEyeJointIndex, parentTransform);
|
||||
|
||||
*/
|
||||
} else {
|
||||
|
||||
Model::updateRig(deltaTime, parentTransform);
|
||||
|
@ -268,34 +271,6 @@ bool operator<(const IndexValue& firstIndex, const IndexValue& secondIndex) {
|
|||
return firstIndex.value < secondIndex.value;
|
||||
}
|
||||
|
||||
void SkeletonModel::applyHandPosition(int jointIndex, const glm::vec3& position) {
|
||||
if (jointIndex == -1 || jointIndex >= _rig->getJointStateCount()) {
|
||||
return;
|
||||
}
|
||||
// NOTE: 'position' is in model-frame
|
||||
setJointPosition(jointIndex, position, glm::quat(), false, -1, false, glm::vec3(0.0f, -1.0f, 0.0f), PALM_PRIORITY);
|
||||
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
glm::vec3 handPosition, elbowPosition;
|
||||
getJointPosition(jointIndex, handPosition);
|
||||
getJointPosition(geometry.joints.at(jointIndex).parentIndex, elbowPosition);
|
||||
glm::vec3 forearmVector = handPosition - elbowPosition;
|
||||
float forearmLength = glm::length(forearmVector);
|
||||
if (forearmLength < EPSILON) {
|
||||
return;
|
||||
}
|
||||
glm::quat handRotation;
|
||||
if (!_rig->getJointStateRotation(jointIndex, handRotation)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// align hand with forearm
|
||||
float sign = (jointIndex == geometry.rightHandJointIndex) ? 1.0f : -1.0f;
|
||||
_rig->applyJointRotationDelta(jointIndex,
|
||||
rotationBetween(handRotation * glm::vec3(-sign, 0.0f, 0.0f), forearmVector),
|
||||
PALM_PRIORITY);
|
||||
}
|
||||
|
||||
void SkeletonModel::applyPalmData(int jointIndex, const PalmData& palm) {
|
||||
if (jointIndex == -1 || jointIndex >= _rig->getJointStateCount()) {
|
||||
return;
|
||||
|
@ -521,6 +496,9 @@ void SkeletonModel::computeBoundingShape() {
|
|||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
AJT: HACK DISABLED
|
||||
|
||||
// BOUNDING SHAPE HACK: before we measure the bounds of the joints we use IK to put the
|
||||
// hands and feet into positions that are more correct than the default pose.
|
||||
|
||||
|
@ -624,6 +602,12 @@ void SkeletonModel::computeBoundingShape() {
|
|||
_rig->restoreJointRotation(i, 1.0f, 1.0f);
|
||||
_rig->restoreJointTranslation(i, 1.0f, 1.0f);
|
||||
}
|
||||
*/
|
||||
|
||||
// AJT: REMOVE HARDCODED BOUNDING VOLUME
|
||||
_boundingCapsuleRadius = 0.5f;
|
||||
_boundingCapsuleHeight = 2.0f;
|
||||
_boundingCapsuleLocalOffset = glm::vec3(0.0f, 1.0f, 0.0f);
|
||||
}
|
||||
|
||||
void SkeletonModel::renderBoundingCollisionShapes(gpu::Batch& batch, float alpha) {
|
||||
|
|
|
@ -27,7 +27,7 @@ public:
|
|||
SkeletonModel(Avatar* owningAvatar, QObject* parent = nullptr, RigPointer rig = nullptr);
|
||||
~SkeletonModel();
|
||||
|
||||
virtual void initJointStates(QVector<JointState> states) override;
|
||||
virtual void initJointStates() override;
|
||||
|
||||
virtual void simulate(float deltaTime, bool fullUpdate = true) override;
|
||||
virtual void updateRig(float deltaTime, glm::mat4 parentTransform) override;
|
||||
|
@ -114,10 +114,6 @@ protected:
|
|||
|
||||
void computeBoundingShape();
|
||||
|
||||
/// \param jointIndex index of joint in model
|
||||
/// \param position position of joint in model-frame
|
||||
void applyHandPosition(int jointIndex, const glm::vec3& position);
|
||||
|
||||
void applyPalmData(int jointIndex, const PalmData& palm);
|
||||
private:
|
||||
|
||||
|
|
|
@ -11,26 +11,6 @@
|
|||
|
||||
#include "AvatarRig.h"
|
||||
|
||||
/// Updates the state of the joint at the specified index.
|
||||
void AvatarRig::updateJointState(int index, glm::mat4 rootTransform) {
|
||||
if (index < 0 || index >= _jointStates.size()) {
|
||||
return; // bail
|
||||
}
|
||||
JointState& state = _jointStates[index];
|
||||
|
||||
// compute model transforms
|
||||
if (index == _rootJointIndex) {
|
||||
state.computeTransform(rootTransform);
|
||||
} else {
|
||||
// guard against out-of-bounds access to _jointStates
|
||||
int parentIndex = state.getParentIndex();
|
||||
if (parentIndex >= 0 && parentIndex < _jointStates.size()) {
|
||||
const JointState& parentState = _jointStates.at(parentIndex);
|
||||
state.computeTransform(parentState.getTransform(), parentState.getTransformChanged());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AvatarRig::setHandPosition(int jointIndex,
|
||||
const glm::vec3& position, const glm::quat& rotation,
|
||||
float scale, float priority) {
|
||||
|
|
|
@ -19,9 +19,8 @@
|
|||
class AvatarRig : public Rig {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
public:
|
||||
~AvatarRig() {}
|
||||
virtual void updateJointState(int index, glm::mat4 rootTransform);
|
||||
virtual void setHandPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation,
|
||||
float scale, float priority);
|
||||
virtual void setJointTranslation(int index, bool valid, const glm::vec3& translation, float priority);
|
||||
|
|
|
@ -11,24 +11,6 @@
|
|||
|
||||
#include "EntityRig.h"
|
||||
|
||||
/// Updates the state of the joint at the specified index.
|
||||
void EntityRig::updateJointState(int index, glm::mat4 rootTransform) {
|
||||
JointState& state = _jointStates[index];
|
||||
|
||||
// compute model transforms
|
||||
int parentIndex = state.getParentIndex();
|
||||
if (parentIndex == -1) {
|
||||
state.computeTransform(rootTransform);
|
||||
} else {
|
||||
// guard against out-of-bounds access to _jointStates
|
||||
if (parentIndex >= 0 && parentIndex < _jointStates.size()) {
|
||||
const JointState& parentState = _jointStates.at(parentIndex);
|
||||
state.computeTransform(parentState.getTransform(), parentState.getTransformChanged());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void EntityRig::setJointState(int index, bool valid, const glm::quat& rotation, const glm::vec3& translation, float priority) {
|
||||
if (index != -1 && index < _jointStates.size()) {
|
||||
JointState& state = _jointStates[index];
|
||||
|
|
|
@ -19,9 +19,8 @@
|
|||
class EntityRig : public Rig {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
public:
|
||||
~EntityRig() {}
|
||||
virtual void updateJointState(int index, glm::mat4 rootTransform);
|
||||
virtual void setHandPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation,
|
||||
float scale, float priority) {}
|
||||
virtual void setJointState(int index, bool valid, const glm::quat& rotation, const glm::vec3& translation, float priority);
|
||||
|
|
|
@ -134,16 +134,40 @@ void Rig::destroyAnimGraph() {
|
|||
_animNode = nullptr;
|
||||
}
|
||||
|
||||
void Rig::initJointStates(QVector<JointState> states, glm::mat4 rootTransform,
|
||||
int rootJointIndex,
|
||||
int leftHandJointIndex,
|
||||
int leftElbowJointIndex,
|
||||
int leftShoulderJointIndex,
|
||||
int rightHandJointIndex,
|
||||
int rightElbowJointIndex,
|
||||
int rightShoulderJointIndex) {
|
||||
_jointStates = states;
|
||||
void Rig::initJointStates(const FBXGeometry& geometry, glm::mat4 modelOffset, int rootJointIndex,
|
||||
int leftHandJointIndex, int leftElbowJointIndex, int leftShoulderJointIndex,
|
||||
int rightHandJointIndex, int rightElbowJointIndex, int rightShoulderJointIndex) {
|
||||
|
||||
_animSkeleton = std::make_shared<AnimSkeleton>(geometry);
|
||||
_relativePoses.resize(_animSkeleton->getNumJoints());
|
||||
|
||||
// AJT: LEGACY
|
||||
{
|
||||
// was Model::createJointStates
|
||||
_jointStates.clear();
|
||||
for (int i = 0; i < geometry.joints.size(); ++i) {
|
||||
const FBXJoint& joint = geometry.joints[i];
|
||||
// store a pointer to the FBXJoint in the JointState
|
||||
JointState state(joint);
|
||||
_jointStates.append(state);
|
||||
}
|
||||
|
||||
// was old Rig::initJointStates
|
||||
// compute model transforms
|
||||
int numStates = _animSkeleton->getNumJoints();
|
||||
for (int i = 0; i < numStates; ++i) {
|
||||
JointState& state = _jointStates[i];
|
||||
int parentIndex = state.getParentIndex();
|
||||
if (parentIndex == -1) {
|
||||
state.initTransform(modelOffset);
|
||||
} else {
|
||||
const JointState& parentState = _jointStates.at(parentIndex);
|
||||
state.initTransform(parentState.getTransform());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// AJT: TODO: we could probaly just look these up by name?
|
||||
_rootJointIndex = rootJointIndex;
|
||||
_leftHandJointIndex = leftHandJointIndex;
|
||||
_leftElbowJointIndex = leftElbowJointIndex;
|
||||
|
@ -152,7 +176,15 @@ void Rig::initJointStates(QVector<JointState> states, glm::mat4 rootTransform,
|
|||
_rightElbowJointIndex = rightElbowJointIndex;
|
||||
_rightShoulderJointIndex = rightShoulderJointIndex;
|
||||
|
||||
initJointTransforms(rootTransform);
|
||||
setModelOffset(modelOffset);
|
||||
}
|
||||
|
||||
bool Rig::jointStatesEmpty() {
|
||||
return _relativePoses.empty();
|
||||
}
|
||||
|
||||
int Rig::getJointStateCount() const {
|
||||
return _relativePoses.size();
|
||||
}
|
||||
|
||||
// We could build and cache a dictionary, too....
|
||||
|
@ -166,7 +198,12 @@ int Rig::indexOfJoint(const QString& jointName) {
|
|||
return -1;
|
||||
}
|
||||
|
||||
void Rig::setModelOffset(const glm::mat4& modelOffset) {
|
||||
_modelOffset = AnimPose(modelOffset);
|
||||
}
|
||||
|
||||
// AJT: REMOVE
|
||||
/*
|
||||
void Rig::initJointTransforms(glm::mat4 rootTransform) {
|
||||
// compute model transforms
|
||||
int numStates = _jointStates.size();
|
||||
|
@ -181,6 +218,7 @@ void Rig::initJointTransforms(glm::mat4 rootTransform) {
|
|||
}
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
void Rig::clearJointTransformTranslation(int jointIndex) {
|
||||
if (jointIndex == -1 || jointIndex >= _jointStates.size()) {
|
||||
|
@ -642,97 +680,20 @@ void Rig::updateAnimations(float deltaTime, glm::mat4 rootTransform) {
|
|||
}
|
||||
}
|
||||
|
||||
// AJT: REMOVE
|
||||
/*
|
||||
for (int i = 0; i < _jointStates.size(); i++) {
|
||||
updateJointState(i, rootTransform);
|
||||
}
|
||||
*/
|
||||
setModelOffset(rootTransform);
|
||||
buildAbsolutePoses();
|
||||
|
||||
for (int i = 0; i < _jointStates.size(); i++) {
|
||||
_jointStates[i].resetTransformChanged();
|
||||
}
|
||||
}
|
||||
|
||||
bool Rig::setJointPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation, bool useRotation,
|
||||
int lastFreeIndex, bool allIntermediatesFree, const glm::vec3& alignment, float priority,
|
||||
const QVector<int>& freeLineage, glm::mat4 rootTransform) {
|
||||
if (jointIndex == -1 || _jointStates.isEmpty()) {
|
||||
return false;
|
||||
}
|
||||
if (freeLineage.isEmpty()) {
|
||||
return false;
|
||||
}
|
||||
if (lastFreeIndex == -1) {
|
||||
lastFreeIndex = freeLineage.last();
|
||||
}
|
||||
|
||||
// this is a cyclic coordinate descent algorithm: see
|
||||
// http://www.ryanjuckett.com/programming/animation/21-cyclic-coordinate-descent-in-2d
|
||||
const int ITERATION_COUNT = 1;
|
||||
glm::vec3 worldAlignment = alignment;
|
||||
for (int i = 0; i < ITERATION_COUNT; i++) {
|
||||
// first, try to rotate the end effector as close as possible to the target rotation, if any
|
||||
glm::quat endRotation;
|
||||
if (useRotation) {
|
||||
JointState& state = _jointStates[jointIndex];
|
||||
|
||||
state.setRotationInBindFrame(rotation, priority);
|
||||
endRotation = state.getRotationInBindFrame();
|
||||
}
|
||||
|
||||
// then, we go from the joint upwards, rotating the end as close as possible to the target
|
||||
glm::vec3 endPosition = extractTranslation(_jointStates[jointIndex].getTransform());
|
||||
for (int j = 1; freeLineage.at(j - 1) != lastFreeIndex; j++) {
|
||||
int index = freeLineage.at(j);
|
||||
JointState& state = _jointStates[index];
|
||||
if (!(state.getIsFree() || allIntermediatesFree)) {
|
||||
continue;
|
||||
}
|
||||
glm::vec3 jointPosition = extractTranslation(state.getTransform());
|
||||
glm::vec3 jointVector = endPosition - jointPosition;
|
||||
glm::quat oldCombinedRotation = state.getRotation();
|
||||
glm::quat combinedDelta;
|
||||
float combinedWeight;
|
||||
if (useRotation) {
|
||||
combinedDelta = safeMix(rotation * glm::inverse(endRotation),
|
||||
rotationBetween(jointVector, position - jointPosition), 0.5f);
|
||||
combinedWeight = 2.0f;
|
||||
|
||||
} else {
|
||||
combinedDelta = rotationBetween(jointVector, position - jointPosition);
|
||||
combinedWeight = 1.0f;
|
||||
}
|
||||
if (alignment != glm::vec3() && j > 1) {
|
||||
jointVector = endPosition - jointPosition;
|
||||
glm::vec3 positionSum;
|
||||
for (int k = j - 1; k > 0; k--) {
|
||||
int index = freeLineage.at(k);
|
||||
updateJointState(index, rootTransform);
|
||||
positionSum += extractTranslation(_jointStates.at(index).getTransform());
|
||||
}
|
||||
glm::vec3 projectedCenterOfMass = glm::cross(jointVector,
|
||||
glm::cross(positionSum / (j - 1.0f) - jointPosition, jointVector));
|
||||
glm::vec3 projectedAlignment = glm::cross(jointVector, glm::cross(worldAlignment, jointVector));
|
||||
const float LENGTH_EPSILON = 0.001f;
|
||||
if (glm::length(projectedCenterOfMass) > LENGTH_EPSILON && glm::length(projectedAlignment) > LENGTH_EPSILON) {
|
||||
combinedDelta = safeMix(combinedDelta, rotationBetween(projectedCenterOfMass, projectedAlignment),
|
||||
1.0f / (combinedWeight + 1.0f));
|
||||
}
|
||||
}
|
||||
state.applyRotationDelta(combinedDelta, priority);
|
||||
glm::quat actualDelta = state.getRotation() * glm::inverse(oldCombinedRotation);
|
||||
endPosition = actualDelta * jointVector + jointPosition;
|
||||
if (useRotation) {
|
||||
endRotation = actualDelta * endRotation;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// now update the joint states from the top
|
||||
for (int j = freeLineage.size() - 1; j >= 0; j--) {
|
||||
updateJointState(freeLineage.at(j), rootTransform);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void Rig::inverseKinematics(int endIndex, glm::vec3 targetPosition, const glm::quat& targetRotation, float priority,
|
||||
const QVector<int>& freeLineage, glm::mat4 rootTransform) {
|
||||
// NOTE: targetRotation is from in model-frame
|
||||
|
@ -1171,15 +1132,7 @@ void Rig::updateFromHandParameters(const HandParameters& params, float dt) {
|
|||
}
|
||||
}
|
||||
|
||||
void Rig::makeAnimSkeleton(const FBXGeometry& fbxGeometry) {
|
||||
if (!_animSkeleton) {
|
||||
_animSkeleton = std::make_shared<AnimSkeleton>(fbxGeometry);
|
||||
}
|
||||
}
|
||||
|
||||
void Rig::initAnimGraph(const QUrl& url, const FBXGeometry& fbxGeometry) {
|
||||
|
||||
makeAnimSkeleton(fbxGeometry);
|
||||
void Rig::initAnimGraph(const QUrl& url) {
|
||||
|
||||
// load the anim graph
|
||||
_animLoader.reset(new AnimNodeLoader(url));
|
||||
|
@ -1200,3 +1153,41 @@ bool Rig::getModelOffset(glm::vec3& modelOffsetOut) const {
|
|||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
void Rig::buildAbsolutePoses() {
|
||||
if (!_animSkeleton) {
|
||||
return;
|
||||
}
|
||||
|
||||
assert(_animSkeleton->getNumJoints() == _relativePoses.size());
|
||||
_absolutePoses.resize(_relativePoses.size());
|
||||
for (int i = 0; i < (int)_relativePoses.size(); i++) {
|
||||
int parentIndex = _animSkeleton->getParentIndex(i);
|
||||
if (parentIndex == -1) {
|
||||
_absolutePoses[i] = _modelOffset * _relativePoses[i];
|
||||
} else {
|
||||
_absolutePoses[i] = _modelOffset * _absolutePoses[parentIndex] * _relativePoses[i];
|
||||
}
|
||||
}
|
||||
|
||||
// AJT: LEGACY
|
||||
{
|
||||
// Build the joint states
|
||||
glm::mat4 rootTransform = (glm::mat4)_modelOffset;
|
||||
for (int i = 0; i < (int)_animSkeleton->getNumJoints(); i++) {
|
||||
JointState& state = _jointStates[i];
|
||||
|
||||
// compute model transforms
|
||||
int parentIndex = state.getParentIndex();
|
||||
if (parentIndex == -1) {
|
||||
state.computeTransform(rootTransform);
|
||||
} else {
|
||||
// guard against out-of-bounds access to _jointStates
|
||||
if (parentIndex >= 0 && parentIndex < _jointStates.size()) {
|
||||
const JointState& parentState = _jointStates.at(parentIndex);
|
||||
state.computeTransform(parentState.getTransform(), parentState.getTransformChanged());
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -10,28 +10,6 @@
|
|||
// Distributed under the Apache License, Version 2.0.
|
||||
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
|
||||
//
|
||||
/*
|
||||
Things we want to be able to do, that I think we cannot do now:
|
||||
* Stop an animation at a given time so that it can be examined visually or in a test harness. (I think we can already stop animation and set frame to a computed float? But does that move the bones?)
|
||||
* Play two animations, blending between them. (Current structure just has one, under script control.)
|
||||
* Fade in an animation over another.
|
||||
* Apply IK, lean, head pointing or other overrides relative to previous position.
|
||||
All of this depends on coordinated state.
|
||||
|
||||
TBD:
|
||||
- What are responsibilities of Animation/AnimationPointer/AnimationCache/AnimationDetails/AnimationObject/AnimationLoop?
|
||||
Is there common/copied code (e.g., ScriptableAvatar::update)?
|
||||
- How do attachments interact with the physics of the attached entity? E.g., do hand joints need to reflect held object
|
||||
physics?
|
||||
- Is there any current need (i.e., for initial campatability) to have multiple animations per role (e.g., idle) with the
|
||||
system choosing randomly?
|
||||
|
||||
- Distribute some doc from here to the right files if it turns out to be correct:
|
||||
- AnimationDetails is a script-useable copy of animation state, analogous to EntityItemProperties, but without anything
|
||||
equivalent to editEntity.
|
||||
But what's the intended difference vs AnimationObjection? Maybe AnimationDetails is to Animation as AnimationObject
|
||||
is to AnimationPointer?
|
||||
*/
|
||||
|
||||
#ifndef __hifi__Rig__
|
||||
#define __hifi__Rig__
|
||||
|
@ -107,19 +85,19 @@ public:
|
|||
void restoreRoleAnimation(const QString& role);
|
||||
void prefetchAnimation(const QString& url);
|
||||
|
||||
void initJointStates(QVector<JointState> states, glm::mat4 rootTransform,
|
||||
int rootJointIndex,
|
||||
int leftHandJointIndex,
|
||||
int leftElbowJointIndex,
|
||||
int leftShoulderJointIndex,
|
||||
int rightHandJointIndex,
|
||||
int rightElbowJointIndex,
|
||||
int rightShoulderJointIndex);
|
||||
bool jointStatesEmpty() { return _jointStates.isEmpty(); };
|
||||
int getJointStateCount() const { return _jointStates.size(); }
|
||||
void initJointStates(const FBXGeometry& geometry, glm::mat4 modelOffset, int rootJointIndex,
|
||||
int leftHandJointIndex, int leftElbowJointIndex, int leftShoulderJointIndex,
|
||||
int rightHandJointIndex, int rightElbowJointIndex, int rightShoulderJointIndex);
|
||||
bool jointStatesEmpty();
|
||||
int getJointStateCount() const;
|
||||
int indexOfJoint(const QString& jointName);
|
||||
|
||||
void setModelOffset(const glm::mat4& modelOffset);
|
||||
|
||||
// AJT: REMOVE
|
||||
/*
|
||||
void initJointTransforms(glm::mat4 rootTransform);
|
||||
*/
|
||||
void clearJointTransformTranslation(int jointIndex);
|
||||
void reset(const QVector<FBXJoint>& fbxJoints);
|
||||
bool getJointStateRotation(int index, glm::quat& rotation) const;
|
||||
|
@ -154,9 +132,6 @@ public:
|
|||
void computeMotionAnimationState(float deltaTime, const glm::vec3& worldPosition, const glm::vec3& worldVelocity, const glm::quat& worldRotation);
|
||||
// Regardless of who started the animations or how many, update the joints.
|
||||
void updateAnimations(float deltaTime, glm::mat4 rootTransform);
|
||||
bool setJointPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation, bool useRotation,
|
||||
int lastFreeIndex, bool allIntermediatesFree, const glm::vec3& alignment, float priority,
|
||||
const QVector<int>& freeLineage, glm::mat4 rootTransform);
|
||||
void inverseKinematics(int endIndex, glm::vec3 targetPosition, const glm::quat& targetRotation, float priority,
|
||||
const QVector<int>& freeLineage, glm::mat4 rootTransform);
|
||||
bool restoreJointPosition(int jointIndex, float fraction, float priority, const QVector<int>& freeLineage);
|
||||
|
@ -171,8 +146,6 @@ public:
|
|||
glm::quat getJointDefaultRotationInParentFrame(int jointIndex);
|
||||
void clearJointStatePriorities();
|
||||
|
||||
virtual void updateJointState(int index, glm::mat4 rootTransform) = 0;
|
||||
|
||||
void updateFromHeadParameters(const HeadParameters& params, float dt);
|
||||
void updateFromEyeParameters(const EyeParameters& params);
|
||||
void updateFromHandParameters(const HandParameters& params, float dt);
|
||||
|
@ -180,8 +153,7 @@ public:
|
|||
virtual void setHandPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation,
|
||||
float scale, float priority) = 0;
|
||||
|
||||
void makeAnimSkeleton(const FBXGeometry& fbxGeometry);
|
||||
void initAnimGraph(const QUrl& url, const FBXGeometry& fbxGeometry);
|
||||
void initAnimGraph(const QUrl& url);
|
||||
|
||||
AnimNode::ConstPointer getAnimNode() const { return _animNode; }
|
||||
AnimSkeleton::ConstPointer getAnimSkeleton() const { return _animSkeleton; }
|
||||
|
@ -193,13 +165,20 @@ public:
|
|||
|
||||
protected:
|
||||
void updateAnimationStateHandlers();
|
||||
void buildAbsolutePoses();
|
||||
|
||||
void updateLeanJoint(int index, float leanSideways, float leanForward, float torsoTwist);
|
||||
void updateNeckJoint(int index, const HeadParameters& params);
|
||||
void updateEyeJoint(int index, const glm::vec3& modelTranslation, const glm::quat& modelRotation, const glm::quat& worldHeadOrientation, const glm::vec3& lookAt, const glm::vec3& saccade);
|
||||
void calcAnimAlpha(float speed, const std::vector<float>& referenceSpeeds, float* alphaOut) const;
|
||||
|
||||
// AJT: TODO: LEGACY
|
||||
QVector<JointState> _jointStates;
|
||||
|
||||
AnimPose _modelOffset;
|
||||
AnimPoseVec _relativePoses;
|
||||
AnimPoseVec _absolutePoses;
|
||||
|
||||
int _rootJointIndex { -1 };
|
||||
|
||||
int _leftHandJointIndex { -1 };
|
||||
|
|
|
@ -106,24 +106,13 @@ void Model::setOffset(const glm::vec3& offset) {
|
|||
_snappedToRegistrationPoint = false;
|
||||
}
|
||||
|
||||
QVector<JointState> Model::createJointStates(const FBXGeometry& geometry) {
|
||||
QVector<JointState> jointStates;
|
||||
for (int i = 0; i < geometry.joints.size(); ++i) {
|
||||
const FBXJoint& joint = geometry.joints[i];
|
||||
// store a pointer to the FBXJoint in the JointState
|
||||
JointState state(joint);
|
||||
jointStates.append(state);
|
||||
}
|
||||
return jointStates;
|
||||
};
|
||||
|
||||
void Model::initJointTransforms() {
|
||||
if (!_geometry || !_geometry->isLoaded()) {
|
||||
return;
|
||||
}
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
_rig->initJointTransforms(parentTransform);
|
||||
glm::mat4 modelOffset = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
_rig->setModelOffset(modelOffset);
|
||||
}
|
||||
|
||||
void Model::init() {
|
||||
|
@ -139,7 +128,6 @@ void Model::reset() {
|
|||
bool Model::updateGeometry() {
|
||||
PROFILE_RANGE(__FUNCTION__);
|
||||
bool needFullUpdate = false;
|
||||
bool needToRebuild = false;
|
||||
|
||||
if (!_geometry || !_geometry->isLoaded()) {
|
||||
// geometry is not ready
|
||||
|
@ -148,17 +136,10 @@ bool Model::updateGeometry() {
|
|||
|
||||
_needsReload = false;
|
||||
|
||||
QSharedPointer<NetworkGeometry> geometry = _geometry;
|
||||
if (_rig->jointStatesEmpty()) {
|
||||
const FBXGeometry& fbxGeometry = geometry->getFBXGeometry();
|
||||
if (fbxGeometry.joints.size() > 0) {
|
||||
initJointStates(createJointStates(fbxGeometry));
|
||||
needToRebuild = true;
|
||||
}
|
||||
}
|
||||
if (_rig->jointStatesEmpty() && _geometry->getFBXGeometry().joints.size() > 0) {
|
||||
initJointStates();
|
||||
|
||||
if (needToRebuild) {
|
||||
const FBXGeometry& fbxGeometry = geometry->getFBXGeometry();
|
||||
const FBXGeometry& fbxGeometry = _geometry->getFBXGeometry();
|
||||
foreach (const FBXMesh& mesh, fbxGeometry.meshes) {
|
||||
MeshState state;
|
||||
state.clusterMatrices.resize(mesh.clusters.size());
|
||||
|
@ -181,9 +162,9 @@ bool Model::updateGeometry() {
|
|||
}
|
||||
|
||||
// virtual
|
||||
void Model::initJointStates(QVector<JointState> states) {
|
||||
void Model::initJointStates() {
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
glm::mat4 modelOffset = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
|
||||
int rootJointIndex = geometry.rootJointIndex;
|
||||
int leftHandJointIndex = geometry.leftHandJointIndex;
|
||||
|
@ -193,7 +174,7 @@ void Model::initJointStates(QVector<JointState> states) {
|
|||
int rightElbowJointIndex = rightHandJointIndex >= 0 ? geometry.joints.at(rightHandJointIndex).parentIndex : -1;
|
||||
int rightShoulderJointIndex = rightElbowJointIndex >= 0 ? geometry.joints.at(rightElbowJointIndex).parentIndex : -1;
|
||||
|
||||
_rig->initJointStates(states, parentTransform,
|
||||
_rig->initJointStates(geometry, modelOffset,
|
||||
rootJointIndex,
|
||||
leftHandJointIndex,
|
||||
leftElbowJointIndex,
|
||||
|
@ -1025,18 +1006,6 @@ void Model::updateClusterMatrices() {
|
|||
}
|
||||
}
|
||||
|
||||
bool Model::setJointPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation, bool useRotation,
|
||||
int lastFreeIndex, bool allIntermediatesFree, const glm::vec3& alignment, float priority) {
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
const QVector<int>& freeLineage = geometry.joints.at(jointIndex).freeLineage;
|
||||
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
|
||||
if (_rig->setJointPosition(jointIndex, position, rotation, useRotation,
|
||||
lastFreeIndex, allIntermediatesFree, alignment, priority, freeLineage, parentTransform)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void Model::inverseKinematics(int endIndex, glm::vec3 targetPosition, const glm::quat& targetRotation, float priority) {
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
const QVector<int>& freeLineage = geometry.joints.at(endIndex).freeLineage;
|
||||
|
@ -1142,8 +1111,6 @@ void Model::segregateMeshGroups() {
|
|||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
const std::vector<std::unique_ptr<NetworkMesh>>& networkMeshes = _geometry->getMeshes();
|
||||
|
||||
_rig->makeAnimSkeleton(geometry);
|
||||
|
||||
// all of our mesh vectors must match in size
|
||||
if ((int)networkMeshes.size() != geometry.meshes.size() ||
|
||||
geometry.meshes.size() != _meshStates.size()) {
|
||||
|
|
|
@ -271,7 +271,7 @@ protected:
|
|||
// returns 'true' if needs fullUpdate after geometry change
|
||||
bool updateGeometry();
|
||||
|
||||
virtual void initJointStates(QVector<JointState> states);
|
||||
virtual void initJointStates();
|
||||
|
||||
void setScaleInternal(const glm::vec3& scale);
|
||||
void scaleToFit();
|
||||
|
@ -280,18 +280,6 @@ protected:
|
|||
void simulateInternal(float deltaTime);
|
||||
virtual void updateRig(float deltaTime, glm::mat4 parentTransform);
|
||||
|
||||
/// \param jointIndex index of joint in model structure
|
||||
/// \param position position of joint in model-frame
|
||||
/// \param rotation rotation of joint in model-frame
|
||||
/// \param useRotation false if rotation should be ignored
|
||||
/// \param lastFreeIndex
|
||||
/// \param allIntermediatesFree
|
||||
/// \param alignment
|
||||
/// \return true if joint exists
|
||||
bool setJointPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation = glm::quat(),
|
||||
bool useRotation = false, int lastFreeIndex = -1, bool allIntermediatesFree = false,
|
||||
const glm::vec3& alignment = glm::vec3(0.0f, -1.0f, 0.0f), float priority = 1.0f);
|
||||
|
||||
/// Restores the indexed joint to its default position.
|
||||
/// \param fraction the fraction of the default position to apply (i.e., 0.25f to slerp one fourth of the way to
|
||||
/// the original position
|
||||
|
@ -315,7 +303,6 @@ protected:
|
|||
private:
|
||||
|
||||
void deleteGeometry();
|
||||
QVector<JointState> createJointStates(const FBXGeometry& geometry);
|
||||
void initJointTransforms();
|
||||
|
||||
QSharedPointer<NetworkGeometry> _collisionGeometry;
|
||||
|
|
Loading…
Reference in a new issue