3
0
Fork 0
mirror of https://github.com/JulianGro/overte.git synced 2025-04-29 16:43:24 +02:00

Merge pull request from hyperlogic/tony/remove-joint-states

Refactor of Rig and MyAvatar animation JavaScript interface
This commit is contained in:
Howard Stearns 2015-11-30 16:28:15 -08:00
commit 6f50d91208
64 changed files with 2028 additions and 3946 deletions

91
examples/kneel.js Normal file
View file

@ -0,0 +1,91 @@
//
// kneel.js
// examples
//
// Created by Anthony Thibault on 11/9/2015
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
// Example of how to play an animation on an avatar.
//
var buttonImageUrl = "https://s3.amazonaws.com/hifi-public/images/tools/kneel.svg";
var windowDimensions = Controller.getViewportDimensions();
var buttonWidth = 37;
var buttonHeight = 46;
var buttonPadding = 10;
var buttonPositionX = windowDimensions.x - buttonPadding - buttonWidth;
var buttonPositionY = (windowDimensions.y - buttonHeight) / 2 - (buttonHeight + buttonPadding);
var kneelDownImageOverlay = {
x: buttonPositionX,
y: buttonPositionY,
width: buttonWidth,
height: buttonHeight,
subImage: { x: 0, y: buttonHeight, width: buttonWidth, height: buttonHeight },
imageURL: buttonImageUrl,
visible: true,
alpha: 1.0
};
var standUpImageOverlay = {
x: buttonPositionX,
y: buttonPositionY,
width: buttonWidth,
height: buttonHeight,
subImage: { x: buttonWidth, y: buttonHeight, width: buttonWidth, height: buttonHeight },
imageURL: buttonImageUrl,
visible: false,
alpha: 1.0
};
var kneelDownButton = Overlays.addOverlay("image", kneelDownImageOverlay);
var standUpButton = Overlays.addOverlay("image", standUpImageOverlay);
var kneeling = false;
var KNEEL_ANIM_URL = "https://hifi-public.s3.amazonaws.com/ozan/anim/kneel/kneel.fbx";
function kneelDown() {
kneeling = true;
var playbackRate = 30; // 30 fps is normal speed.
var loopFlag = false;
var startFrame = 0;
var endFrame = 82;
// This will completly override all motion from the default animation system
// including inverse kinematics for hand and head controllers.
MyAvatar.overrideAnimation(KNEEL_ANIM_URL, playbackRate, loopFlag, startFrame, endFrame);
Overlays.editOverlay(kneelDownButton, { visible: false });
Overlays.editOverlay(standUpButton, { visible: true });
}
function standUp() {
kneeling = false;
// this will restore all motion from the default animation system.
// inverse kinematics will work again normally.
MyAvatar.restoreAnimation();
Overlays.editOverlay(standUpButton, { visible: false });
Overlays.editOverlay(kneelDownButton, { visible: true });
}
Controller.mousePressEvent.connect(function (event) {
var clickedOverlay = Overlays.getOverlayAtPoint({ x: event.x, y: event.y });
if (clickedOverlay == kneelDownButton) {
kneelDown();
} else if (clickedOverlay == standUpButton) {
standUp();
}
});
Script.scriptEnding.connect(function() {
Overlays.deleteOverlay(kneelDownButton);
Overlays.deleteOverlay(standUpButton);
});

View file

@ -75,7 +75,7 @@ function updateJoints(factor){
for (var i = 0; i < startPoseAndTransition.length; i++){
var scaledTransition = Vec3.multiply(startPoseAndTransition[i].transition, factor);
var rotation = Vec3.sum(startPoseAndTransition[i].start, scaledTransition);
MyAvatar.setJointData(startPoseAndTransition[i].joint, Quat.fromVec3Degrees( rotation ));
MyAvatar.setJointRotation(startPoseAndTransition[i].joint, Quat.fromVec3Degrees( rotation ));
}
}
@ -282,7 +282,8 @@ function update(deltaTime){
MyAvatar.position.z != avatarOldPosition.z ||
locationChanged) {
avatarOldPosition = MyAvatar.position;
/*
var SEARCH_RADIUS = 50;
var foundModels = Entities.findEntities(MyAvatar.position, SEARCH_RADIUS);
// Let's remove indicator that got out of radius
@ -306,6 +307,7 @@ function update(deltaTime){
if (hiddingSeats && passedTime >= animationLenght) {
showIndicators(true);
}
*/
}
}
var oldHost = location.hostname;

34
examples/theBird.js Normal file
View file

@ -0,0 +1,34 @@
//
// theBird.js
// examples
//
// Created by Anthony Thibault on 11/9/2015
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
// Example of how to play an animation on an avatar.
//
var THE_BIRD_RIGHT_URL = "https://hifi-public.s3.amazonaws.com/ozan/anim/the_bird/the_bird_right.fbx";
var roles = MyAvatar.getAnimationRoles();
var i, l = roles.length
print("getAnimationRoles()");
for (i = 0; i < l; i++) {
print(roles[i]);
}
MyAvatar.prefetchAnimation(THE_BIRD_RIGHT_URL);
// replace point animations with the bird!
MyAvatar.overrideRoleAnimation("rightHandPointIntro", THE_BIRD_RIGHT_URL, 30, false, 0, 12);
MyAvatar.overrideRoleAnimation("rightHandPointHold", THE_BIRD_RIGHT_URL, 30, false, 12, 12);
MyAvatar.overrideRoleAnimation("rightHandPointOutro", THE_BIRD_RIGHT_URL, 30, false, 19, 30);
Script.scriptEnding.connect(function() {
MyAvatar.restoreRoleAnimation("rightHandPointIntro");
MyAvatar.restoreRoleAnimation("rightHandPointHold");
MyAvatar.restoreRoleAnimation("rightHandPointOutro");
});

View file

@ -2555,11 +2555,12 @@ void Application::init() {
setAvatarUpdateThreading();
}
const bool ENABLE_AVATAR_UPDATE_THREADING = false;
void Application::setAvatarUpdateThreading() {
setAvatarUpdateThreading(Menu::getInstance()->isOptionChecked(MenuOption::EnableAvatarUpdateThreading));
setAvatarUpdateThreading(ENABLE_AVATAR_UPDATE_THREADING);
}
void Application::setRawAvatarUpdateThreading() {
setRawAvatarUpdateThreading(Menu::getInstance()->isOptionChecked(MenuOption::EnableAvatarUpdateThreading));
setRawAvatarUpdateThreading(ENABLE_AVATAR_UPDATE_THREADING);
}
void Application::setRawAvatarUpdateThreading(bool isThreaded) {
if (_avatarUpdate) {
@ -2577,17 +2578,11 @@ void Application::setAvatarUpdateThreading(bool isThreaded) {
}
auto myAvatar = getMyAvatar();
bool isRigEnabled = myAvatar->getEnableRigAnimations();
bool isGraphEnabled = myAvatar->getEnableAnimGraph();
if (_avatarUpdate) {
_avatarUpdate->terminate(); // Must be before we shutdown anim graph.
}
myAvatar->setEnableRigAnimations(false);
myAvatar->setEnableAnimGraph(false);
_avatarUpdate = new AvatarUpdate();
_avatarUpdate->initialize(isThreaded);
myAvatar->setEnableRigAnimations(isRigEnabled);
myAvatar->setEnableAnimGraph(isGraphEnabled);
}
void Application::updateLOD() {
@ -2970,11 +2965,6 @@ void Application::update(float deltaTime) {
loadViewFrustum(_myCamera, _viewFrustum);
}
// Update animation debug draw renderer
{
AnimDebugDraw::getInstance().update();
}
quint64 now = usecTimestampNow();
// Update my voxel servers with my current voxel query...
@ -3534,6 +3524,8 @@ void Application::displaySide(RenderArgs* renderArgs, Camera& theCamera, bool se
myAvatar->preRender(renderArgs);
myAvatar->endRender();
// Update animation debug draw renderer
AnimDebugDraw::getInstance().update();
activeRenderingThread = QThread::currentThread();
PROFILE_RANGE(__FUNCTION__);
@ -4365,10 +4357,6 @@ void Application::stopAllScripts(bool restart) {
it.value()->stop();
qCDebug(interfaceapp) << "stopping script..." << it.key();
}
// HACK: ATM scripts cannot set/get their animation priorities, so we clear priorities
// whenever a script stops in case it happened to have been setting joint rotations.
// TODO: expose animation priorities and provide a layered animation control system.
getMyAvatar()->clearJointAnimationPriorities();
getMyAvatar()->clearScriptableSettings();
}
@ -4384,10 +4372,6 @@ bool Application::stopScript(const QString& scriptHash, bool restart) {
scriptEngine->stop();
stoppedScript = true;
qCDebug(interfaceapp) << "stopping script..." << scriptHash;
// HACK: ATM scripts cannot set/get their animation priorities, so we clear priorities
// whenever a script stops in case it happened to have been setting joint rotations.
// TODO: expose animation priorities and provide a layered animation control system.
getMyAvatar()->clearJointAnimationPriorities();
}
if (_scriptEnginesHash.empty()) {
getMyAvatar()->clearScriptableSettings();

View file

@ -145,8 +145,6 @@ Menu::Menu() {
addActionToQMenuAndActionHash(editMenu, MenuOption::Attachments, 0,
dialogsManager.data(), SLOT(editAttachments()));
addActionToQMenuAndActionHash(editMenu, MenuOption::Animations, 0,
dialogsManager.data(), SLOT(editAnimations()));
MenuWrapper* toolsMenu = addMenu("Tools");
addActionToQMenuAndActionHash(toolsMenu, MenuOption::ScriptEditor, Qt::ALT | Qt::Key_S,
@ -443,16 +441,12 @@ Menu::Menu() {
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::RenderFocusIndicator, 0, false);
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::ShowWhosLookingAtMe, 0, false);
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::FixGaze, 0, false);
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::EnableAvatarUpdateThreading, 0, false,
qApp, SLOT(setAvatarUpdateThreading(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::EnableRigAnimations, 0, false,
avatar, SLOT(setEnableRigAnimations(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::EnableAnimGraph, 0, true,
avatar, SLOT(setEnableAnimGraph(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::AnimDebugDrawBindPose, 0, false,
avatar, SLOT(setEnableDebugDrawBindPose(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::AnimDebugDrawDefaultPose, 0, false,
avatar, SLOT(setEnableDebugDrawDefaultPose(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::AnimDebugDrawAnimPose, 0, false,
avatar, SLOT(setEnableDebugDrawAnimPose(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::AnimDebugDrawPosition, 0, false,
avatar, SLOT(setEnableDebugDrawPosition(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::MeshVisible, 0, true,
avatar, SLOT(setEnableMeshVisible(bool)));
addCheckableActionToQMenuAndActionHash(avatarDebugMenu, MenuOption::DisableEyelidAdjustment, 0, false);
@ -464,7 +458,6 @@ Menu::Menu() {
addCheckableActionToQMenuAndActionHash(handOptionsMenu, MenuOption::EnableHandMouseInput, 0, false);
addCheckableActionToQMenuAndActionHash(handOptionsMenu, MenuOption::LowVelocityFilter, 0, true,
qApp, SLOT(setLowVelocityFilter(bool)));
addCheckableActionToQMenuAndActionHash(handOptionsMenu, MenuOption::ShowIKConstraints, 0, false);
MenuWrapper* leapOptionsMenu = handOptionsMenu->addMenu("Leap Motion");
addCheckableActionToQMenuAndActionHash(leapOptionsMenu, MenuOption::LeapMotionOnHMD, 0, false);

View file

@ -131,7 +131,8 @@ namespace MenuOption {
const QString AddressBar = "Show Address Bar";
const QString Animations = "Animations...";
const QString AnimDebugDrawAnimPose = "Debug Draw Animation";
const QString AnimDebugDrawBindPose = "Debug Draw Bind Pose";
const QString AnimDebugDrawDefaultPose = "Debug Draw Default Pose";
const QString AnimDebugDrawPosition= "Debug Draw Position";
const QString Antialiasing = "Antialiasing";
const QString AssetMigration = "ATP Asset Migration";
const QString Atmosphere = "Atmosphere";
@ -188,10 +189,7 @@ namespace MenuOption {
const QString EchoServerAudio = "Echo Server Audio";
const QString EditEntitiesHelp = "Edit Entities Help...";
const QString Enable3DTVMode = "Enable 3DTV Mode";
const QString EnableAvatarUpdateThreading = "Enable Avatar Update Threading";
const QString EnableAnimGraph = "Enable Anim Graph";
const QString EnableCharacterController = "Enable avatar collisions";
const QString EnableRigAnimations = "Enable Rig Animations";
const QString ExpandMyAvatarSimulateTiming = "Expand /myAvatar/simulation";
const QString ExpandMyAvatarTiming = "Expand /myAvatar";
const QString ExpandOtherAvatarTiming = "Expand /otherAvatar";
@ -271,7 +269,6 @@ namespace MenuOption {
const QString ScriptedMotorControl = "Enable Scripted Motor Control";
const QString ShowDSConnectTable = "Show Domain Connection Timing";
const QString ShowBordersEntityNodes = "Show Entity Nodes";
const QString ShowIKConstraints = "Show IK Constraints";
const QString ShowRealtimeEntityStats = "Show Realtime Entity Stats";
const QString ShowWhosLookingAtMe = "Show Who's Looking at Me";
const QString StandingHMDSensorMode = "Standing HMD Sensor Mode";

View file

@ -43,7 +43,7 @@
#include "Util.h"
#include "world.h"
#include "InterfaceLogging.h"
#include "EntityRig.h"
#include <Rig.h>
using namespace std;
@ -223,12 +223,7 @@ void Avatar::simulate(float deltaTime) {
if (!_shouldRenderBillboard && !_shouldSkipRender && inViewFrustum) {
{
PerformanceTimer perfTimer("skeleton");
for (int i = 0; i < _jointData.size(); i++) {
const JointData& data = _jointData.at(i);
_skeletonModel.setJointRotation(i, data.rotationSet, data.rotation, 1.0f);
_skeletonModel.setJointTranslation(i, data.translationSet, data.translation, 1.0f);
}
_skeletonModel.getRig()->copyJointsFromJointData(_jointData);
_skeletonModel.simulate(deltaTime, _hasNewJointRotations || _hasNewJointTranslations);
simulateAttachments(deltaTime);
_hasNewJointRotations = false;
@ -272,7 +267,7 @@ bool Avatar::isLookingAtMe(AvatarSharedPointer avatar) {
const float HEAD_SPHERE_RADIUS = 0.1f;
glm::vec3 theirLookAt = dynamic_pointer_cast<Avatar>(avatar)->getHead()->getLookAtPosition();
glm::vec3 myEyePosition = getHead()->getEyePosition();
return glm::distance(theirLookAt, myEyePosition) <= (HEAD_SPHERE_RADIUS * getScale());
}
@ -522,8 +517,8 @@ void Avatar::render(RenderArgs* renderArgs, const glm::vec3& cameraPosition) {
eyeDiameter = DEFAULT_EYE_DIAMETER;
}
DependencyManager::get<DeferredLightingEffect>()->renderSolidSphereInstance(batch,
Transform(transform).postScale(eyeDiameter * _scale / 2.0f + RADIUS_INCREMENT),
DependencyManager::get<DeferredLightingEffect>()->renderSolidSphereInstance(batch,
Transform(transform).postScale(eyeDiameter * _scale / 2.0f + RADIUS_INCREMENT),
glm::vec4(LOOKING_AT_ME_COLOR, alpha));
position = getHead()->getRightEyePosition();
@ -533,7 +528,7 @@ void Avatar::render(RenderArgs* renderArgs, const glm::vec3& cameraPosition) {
eyeDiameter = DEFAULT_EYE_DIAMETER;
}
DependencyManager::get<DeferredLightingEffect>()->renderSolidSphereInstance(batch,
Transform(transform).postScale(eyeDiameter * _scale / 2.0f + RADIUS_INCREMENT),
Transform(transform).postScale(eyeDiameter * _scale / 2.0f + RADIUS_INCREMENT),
glm::vec4(LOOKING_AT_ME_COLOR, alpha));
}
@ -581,7 +576,7 @@ void Avatar::render(RenderArgs* renderArgs, const glm::vec3& cameraPosition) {
if (!isMyAvatar() || cameraMode != CAMERA_MODE_FIRST_PERSON) {
auto& frustum = *renderArgs->_viewFrustum;
auto textPosition = getDisplayNamePosition();
if (frustum.pointInFrustum(textPosition, true) == ViewFrustum::INSIDE) {
renderDisplayName(batch, frustum, textPosition);
}
@ -637,7 +632,7 @@ void Avatar::fixupModelsInScene() {
void Avatar::renderBody(RenderArgs* renderArgs, ViewFrustum* renderFrustum, float glowLevel) {
fixupModelsInScene();
{
if (_shouldRenderBillboard || !(_skeletonModel.isRenderable() && getHead()->getFaceModel().isRenderable())) {
// render the billboard until both models are loaded
@ -666,7 +661,7 @@ void Avatar::simulateAttachments(float deltaTime) {
glm::vec3 jointPosition;
glm::quat jointRotation;
if (_skeletonModel.getJointPositionInWorldFrame(jointIndex, jointPosition) &&
_skeletonModel.getJointCombinedRotation(jointIndex, jointRotation)) {
_skeletonModel.getJointRotationInWorldFrame(jointIndex, jointRotation)) {
model->setTranslation(jointPosition + jointRotation * attachment.translation * _scale);
model->setRotation(jointRotation * attachment.rotation);
model->setScaleToFit(true, _scale * attachment.scale, true); // hack to force rescale
@ -701,7 +696,7 @@ void Avatar::renderBillboard(RenderArgs* renderArgs) {
glm::quat rotation = getOrientation();
glm::vec3 cameraVector = glm::inverse(rotation) * (qApp->getCamera()->getPosition() - _position);
rotation = rotation * glm::angleAxis(atan2f(-cameraVector.x, -cameraVector.z), glm::vec3(0.0f, 1.0f, 0.0f));
// compute the size from the billboard camera parameters and scale
float size = getBillboardSize();
@ -714,7 +709,7 @@ void Avatar::renderBillboard(RenderArgs* renderArgs) {
glm::vec2 bottomRight(1.0f, 1.0f);
glm::vec2 texCoordTopLeft(0.0f, 0.0f);
glm::vec2 texCoordBottomRight(1.0f, 1.0f);
gpu::Batch& batch = *renderArgs->_batch;
PROFILE_RANGE_BATCH(batch, __FUNCTION__);
batch.setResourceTexture(0, _billboardTexture->getGPUTexture());
@ -747,29 +742,29 @@ glm::vec3 Avatar::getDisplayNamePosition() const {
glm::vec3 namePosition(0.0f);
glm::vec3 bodyUpDirection = getBodyUpDirection();
DEBUG_VALUE("bodyUpDirection =", bodyUpDirection);
if (getSkeletonModel().getNeckPosition(namePosition)) {
float headHeight = getHeadHeight();
DEBUG_VALUE("namePosition =", namePosition);
DEBUG_VALUE("headHeight =", headHeight);
static const float SLIGHTLY_ABOVE = 1.1f;
namePosition += bodyUpDirection * headHeight * SLIGHTLY_ABOVE;
} else {
const float HEAD_PROPORTION = 0.75f;
float billboardSize = getBillboardSize();
DEBUG_VALUE("_position =", _position);
DEBUG_VALUE("billboardSize =", billboardSize);
namePosition = _position + bodyUpDirection * (billboardSize * HEAD_PROPORTION);
}
if (glm::any(glm::isnan(namePosition)) || glm::any(glm::isinf(namePosition))) {
qCWarning(interfaceapp) << "Invalid display name position" << namePosition
<< ", setting is to (0.0f, 0.5f, 0.0f)";
namePosition = glm::vec3(0.0f, 0.5f, 0.0f);
}
return namePosition;
}
@ -777,16 +772,16 @@ Transform Avatar::calculateDisplayNameTransform(const ViewFrustum& frustum, cons
Q_ASSERT_X(frustum.pointInFrustum(textPosition, true) == ViewFrustum::INSIDE,
"Avatar::calculateDisplayNameTransform", "Text not in viewfrustum.");
glm::vec3 toFrustum = frustum.getPosition() - textPosition;
// Compute orientation
// If x and z are 0, atan(x, z) adais undefined, so default to 0 degrees
const float yawRotation = (toFrustum.x == 0.0f && toFrustum.z == 0.0f) ? 0.0f : glm::atan(toFrustum.x, toFrustum.z);
glm::quat orientation = glm::quat(glm::vec3(0.0f, yawRotation, 0.0f));
// Compute correct scale to apply
static const float DESIRED_HEIGHT_RAD = glm::radians(1.5f);
float scale = glm::length(toFrustum) * glm::tan(DESIRED_HEIGHT_RAD);
// Set transform
Transform result;
result.setTranslation(textPosition);
@ -794,7 +789,7 @@ Transform Avatar::calculateDisplayNameTransform(const ViewFrustum& frustum, cons
result.setScale(scale);
// raise by half the scale up so that textPosition be the bottom
result.postTranslate(Vectors::UP / 2.0f);
return result;
}
@ -822,14 +817,14 @@ void Avatar::renderDisplayName(gpu::Batch& batch, const ViewFrustum& frustum, co
}
renderedDisplayName += statsFormat.arg(QString::number(kilobitsPerSecond, 'f', 2)).arg(getReceiveRate());
}
// Compute display name extent/position offset
const glm::vec2 extent = renderer->computeExtent(renderedDisplayName);
if (!glm::any(glm::isCompNull(extent, EPSILON))) {
const QRect nameDynamicRect = QRect(0, 0, (int)extent.x, (int)extent.y);
const int text_x = -nameDynamicRect.width() / 2;
const int text_y = -nameDynamicRect.height() / 2;
// Compute background position/size
static const float SLIGHTLY_IN_FRONT = 0.1f;
static const float BORDER_RELATIVE_SIZE = 0.1f;
@ -840,12 +835,12 @@ void Avatar::renderDisplayName(gpu::Batch& batch, const ViewFrustum& frustum, co
const int width = nameDynamicRect.width() + 2.0f * border;
const int height = nameDynamicRect.height() + 2.0f * border;
const int bevelDistance = BEVEL_FACTOR * height;
// Display name and background colors
glm::vec4 textColor(0.93f, 0.93f, 0.93f, _displayNameAlpha);
glm::vec4 backgroundColor(0.2f, 0.2f, 0.2f,
(_displayNameAlpha / DISPLAYNAME_ALPHA) * DISPLAYNAME_BACKGROUND_ALPHA);
// Compute display name transform
auto textTransform = calculateDisplayNameTransform(frustum, textPosition);
// Test on extent above insures abs(height) > 0.0f
@ -861,7 +856,7 @@ void Avatar::renderDisplayName(gpu::Batch& batch, const ViewFrustum& frustum, co
// Render actual name
QByteArray nameUTF8 = renderedDisplayName.toLocal8Bit();
// Render text slightly in front to avoid z-fighting
textTransform.postTranslate(glm::vec3(0.0f, 0.0f, SLIGHTLY_IN_FRONT * renderer->getFontSize()));
batch.setModelTransform(textTransform);
@ -963,52 +958,6 @@ glm::vec3 Avatar::getJointPosition(const QString& name) const {
return position;
}
glm::quat Avatar::getJointCombinedRotation(int index) const {
if (QThread::currentThread() != thread()) {
glm::quat rotation;
QMetaObject::invokeMethod(const_cast<Avatar*>(this), "getJointCombinedRotation", Qt::BlockingQueuedConnection,
Q_RETURN_ARG(glm::quat, rotation), Q_ARG(const int, index));
return rotation;
}
glm::quat rotation;
_skeletonModel.getJointCombinedRotation(index, rotation);
return rotation;
}
glm::quat Avatar::getJointCombinedRotation(const QString& name) const {
if (QThread::currentThread() != thread()) {
glm::quat rotation;
QMetaObject::invokeMethod(const_cast<Avatar*>(this), "getJointCombinedRotation", Qt::BlockingQueuedConnection,
Q_RETURN_ARG(glm::quat, rotation), Q_ARG(const QString&, name));
return rotation;
}
glm::quat rotation;
_skeletonModel.getJointCombinedRotation(getJointIndex(name), rotation);
return rotation;
}
const float SCRIPT_PRIORITY = DEFAULT_PRIORITY + 1.0f;
void Avatar::setJointModelPositionAndOrientation(int index, glm::vec3 position, const glm::quat& rotation) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(const_cast<Avatar*>(this), "setJointModelPositionAndOrientation",
Qt::AutoConnection, Q_ARG(const int, index), Q_ARG(const glm::vec3, position),
Q_ARG(const glm::quat&, rotation));
} else {
_skeletonModel.inverseKinematics(index, position, rotation, SCRIPT_PRIORITY);
}
}
void Avatar::setJointModelPositionAndOrientation(const QString& name, glm::vec3 position, const glm::quat& rotation) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(const_cast<Avatar*>(this), "setJointModelPositionAndOrientation",
Qt::AutoConnection, Q_ARG(const QString&, name), Q_ARG(const glm::vec3, position),
Q_ARG(const glm::quat&, rotation));
} else {
_skeletonModel.inverseKinematics(getJointIndex(name), position, rotation, SCRIPT_PRIORITY);
}
}
void Avatar::scaleVectorRelativeToPosition(glm::vec3 &positionToScale) const {
//Scale a world space vector as if it was relative to the position
positionToScale = _position + _scale * (positionToScale - _position);
@ -1037,7 +986,7 @@ void Avatar::setAttachmentData(const QVector<AttachmentData>& attachmentData) {
if (_unusedAttachments.size() > 0) {
model = _unusedAttachments.takeFirst();
} else {
model = new Model(std::make_shared<EntityRig>(), this);
model = new Model(std::make_shared<Rig>(), this);
}
model->init();
_attachmentModels.append(model);

View file

@ -26,6 +26,7 @@
#include "Head.h"
#include "SkeletonModel.h"
#include "world.h"
#include "Rig.h"
namespace render {
template <> const ItemKey payloadGetKey(const AvatarSharedPointer& avatar);
@ -65,7 +66,7 @@ public:
typedef render::Payload<AvatarData> Payload;
typedef std::shared_ptr<render::Item::PayloadInterface> PayloadPointer;
void init();
void simulate(float deltaTime);
@ -100,20 +101,20 @@ public:
float getLODDistance() const;
virtual bool isMyAvatar() const { return false; }
virtual QVector<glm::quat> getJointRotations() const;
virtual glm::quat getJointRotation(int index) const;
virtual glm::vec3 getJointTranslation(int index) const;
virtual int getJointIndex(const QString& name) const;
virtual QStringList getJointNames() const;
virtual void setFaceModelURL(const QUrl& faceModelURL);
virtual void setSkeletonModelURL(const QUrl& skeletonModelURL);
virtual void setAttachmentData(const QVector<AttachmentData>& attachmentData);
virtual void setBillboard(const QByteArray& billboard);
void setShowDisplayName(bool showDisplayName);
virtual int parseDataFromBuffer(const QByteArray& buffer);
static void renderJointConnectingCone( gpu::Batch& batch, glm::vec3 position1, glm::vec3 position2,
@ -124,16 +125,9 @@ public:
Q_INVOKABLE void setSkeletonOffset(const glm::vec3& offset);
Q_INVOKABLE glm::vec3 getSkeletonOffset() { return _skeletonOffset; }
virtual glm::vec3 getSkeletonPosition() const;
Q_INVOKABLE glm::vec3 getJointPosition(int index) const;
Q_INVOKABLE glm::vec3 getJointPosition(const QString& name) const;
Q_INVOKABLE glm::quat getJointCombinedRotation(int index) const;
Q_INVOKABLE glm::quat getJointCombinedRotation(const QString& name) const;
Q_INVOKABLE void setJointModelPositionAndOrientation(int index, const glm::vec3 position, const glm::quat& rotation);
Q_INVOKABLE void setJointModelPositionAndOrientation(const QString& name, const glm::vec3 position,
const glm::quat& rotation);
Q_INVOKABLE glm::vec3 getNeckPosition() const;
Q_INVOKABLE glm::vec3 getAcceleration() const { return _acceleration; }
@ -196,9 +190,9 @@ protected:
glm::vec3 _worldUpDirection;
float _stringLength;
bool _moving; ///< set when position is changing
bool isLookingAtMe(AvatarSharedPointer avatar);
// protected methods...
glm::vec3 getBodyRightDirection() const { return getOrientation() * IDENTITY_RIGHT; }
glm::vec3 getBodyUpDirection() const { return getOrientation() * IDENTITY_UP; }

View file

@ -35,7 +35,7 @@
#include "Menu.h"
#include "MyAvatar.h"
#include "SceneScriptingInterface.h"
#include "AvatarRig.h"
#include <Rig.h>
// 70 times per second - target is 60hz, but this helps account for any small deviations
// in the update loop
@ -66,7 +66,7 @@ AvatarManager::AvatarManager(QObject* parent) :
{
// register a meta type for the weak pointer we'll use for the owning avatar mixer for each avatar
qRegisterMetaType<QWeakPointer<Node> >("NodeWeakPointer");
_myAvatar = std::make_shared<MyAvatar>(std::make_shared<AvatarRig>());
_myAvatar = std::make_shared<MyAvatar>(std::make_shared<Rig>());
auto& packetReceiver = DependencyManager::get<NodeList>()->getPacketReceiver();
packetReceiver.registerListener(PacketType::BulkAvatarData, this, "processAvatarDataPacket");
@ -205,7 +205,7 @@ void AvatarManager::simulateAvatarFades(float deltaTime) {
}
AvatarSharedPointer AvatarManager::newSharedAvatar() {
return std::make_shared<Avatar>(std::make_shared<AvatarRig>());
return std::make_shared<Avatar>(std::make_shared<Rig>());
}
AvatarSharedPointer AvatarManager::addAvatar(const QUuid& sessionUUID, const QWeakPointer<Node>& mixerWeakPointer) {
@ -356,7 +356,8 @@ void AvatarManager::handleCollisionEvents(const CollisionEvents& collisionEvents
AudioInjector::playSound(collisionSoundURL, energyFactorOfFull, AVATAR_STRETCH_FACTOR, myAvatar->getPosition());
myAvatar->collisionWithEntity(collision);
return; }
return;
}
}
}
}

View file

@ -44,9 +44,12 @@ void AvatarUpdate::synchronousProcess() {
bool AvatarUpdate::process() {
PerformanceTimer perfTimer("AvatarUpdate");
quint64 start = usecTimestampNow();
quint64 deltaMicroseconds = start - _lastAvatarUpdate;
_lastAvatarUpdate = start;
quint64 deltaMicroseconds = 0;
if (_lastAvatarUpdate > 0) {
deltaMicroseconds = start - _lastAvatarUpdate;
}
float deltaSeconds = (float) deltaMicroseconds / (float) USECS_PER_SECOND;
_lastAvatarUpdate = start;
qApp->setAvatarSimrateSample(1.0f / deltaSeconds);
QSharedPointer<AvatarManager> manager = DependencyManager::get<AvatarManager>();

View file

@ -32,10 +32,7 @@ void FaceModel::simulate(float deltaTime, bool fullUpdate) {
neckPosition = owningAvatar->getPosition();
}
setTranslation(neckPosition);
glm::quat neckParentRotation;
if (!owningAvatar->getSkeletonModel().getNeckParentRotationFromDefaultOrientation(neckParentRotation)) {
neckParentRotation = owningAvatar->getOrientation();
}
glm::quat neckParentRotation = owningAvatar->getOrientation();
setRotation(neckParentRotation);
setScale(glm::vec3(1.0f, 1.0f, 1.0f) * _owningHead->getScale());

View file

@ -26,7 +26,7 @@
#include "devices/DdeFaceTracker.h"
#include "devices/EyeTracker.h"
#include "devices/Faceshift.h"
#include "AvatarRig.h"
#include <Rig.h>
using namespace std;
@ -62,7 +62,7 @@ Head::Head(Avatar* owningAvatar) :
_isLookingAtMe(false),
_lookingAtMeStarted(0),
_wasLastLookingAtMe(0),
_faceModel(this, std::make_shared<AvatarRig>()),
_faceModel(this, std::make_shared<Rig>()),
_leftEyeLookAtID(DependencyManager::get<GeometryCache>()->allocateID()),
_rightEyeLookAtID(DependencyManager::get<GeometryCache>()->allocateID())
{

View file

@ -21,7 +21,6 @@
#include <AccountManager.h>
#include <AddressManager.h>
#include <AnimationHandle.h>
#include <AudioClient.h>
#include <DependencyManager.h>
#include <display-plugins/DisplayPlugin.h>
@ -218,16 +217,9 @@ QByteArray MyAvatar::toByteArray(bool cullSmallChanges, bool sendAll) {
}
void MyAvatar::reset(bool andReload) {
// Gather animation mode...
// This should be simpler when we have only graph animations always on.
bool isRig = _rig->getEnableRig();
// seting rig animation to true, below, will clear the graph animation menu item, so grab it now.
bool isGraph = _rig->getEnableAnimGraph() || Menu::getInstance()->isOptionChecked(MenuOption::EnableAnimGraph);
// ... and get to sane configuration where other activity won't bother us.
if (andReload) {
qApp->setRawAvatarUpdateThreading(false);
_rig->disableHands = true;
setEnableRigAnimations(true);
}
// Reset dynamic state.
@ -263,19 +255,6 @@ void MyAvatar::reset(bool andReload) {
//_bodySensorMatrix = newBodySensorMatrix;
//updateSensorToWorldMatrix(); // Uses updated position/orientation and _bodySensorMatrix changes
_skeletonModel.simulate(0.1f); // non-zero
setEnableRigAnimations(false);
_skeletonModel.simulate(0.1f);
}
if (isRig) {
setEnableRigAnimations(true);
Menu::getInstance()->setIsOptionChecked(MenuOption::EnableRigAnimations, true);
} else if (isGraph) {
setEnableAnimGraph(true);
Menu::getInstance()->setIsOptionChecked(MenuOption::EnableAnimGraph, true);
}
if (andReload) {
_rig->disableHands = false;
qApp->setRawAvatarUpdateThreading();
}
}
@ -359,13 +338,7 @@ void MyAvatar::simulate(float deltaTime) {
{
PerformanceTimer perfTimer("joints");
// copy out the skeleton joints from the model
_jointData.resize(_rig->getJointStateCount());
for (int i = 0; i < _jointData.size(); i++) {
JointData& data = _jointData[i];
data.rotationSet |= _rig->getJointStateRotation(i, data.rotation);
data.translationSet |= _rig->getJointStateTranslation(i, data.translation);
}
_rig->copyJointsIntoJointData(_jointData);
}
{
@ -450,12 +423,6 @@ void MyAvatar::updateHMDFollowVelocity() {
// This is so the correct camera can be used for rendering.
void MyAvatar::updateSensorToWorldMatrix() {
#ifdef DEBUG_RENDERING
// draw marker about avatar's position
const glm::vec4 red(1.0f, 0.0f, 0.0f, 1.0f);
DebugDraw::getInstance().addMyAvatarMarker("pos", glm::quat(), glm::vec3(), red);
#endif
// update the sensor mat so that the body position will end up in the desired
// position when driven from the head.
glm::mat4 desiredMat = createMatFromQuatAndPos(getOrientation(), getPosition());
@ -602,12 +569,6 @@ void MyAvatar::render(RenderArgs* renderArgs, const glm::vec3& cameraPosition) {
}
Avatar::render(renderArgs, cameraPosition);
// don't display IK constraints in shadow mode
if (Menu::getInstance()->isOptionChecked(MenuOption::ShowIKConstraints) &&
renderArgs && renderArgs->_batch) {
_skeletonModel.renderIKConstraints(*renderArgs->_batch);
}
}
void MyAvatar::clearReferential() {
@ -636,76 +597,56 @@ bool MyAvatar::setJointReferential(const QUuid& id, int jointIndex) {
}
}
void MyAvatar::startAnimation(const QString& url, float fps, float priority,
bool loop, bool hold, float firstFrame, float lastFrame, const QStringList& maskedJoints) {
void MyAvatar::overrideAnimation(const QString& url, float fps, bool loop, float firstFrame, float lastFrame) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "startAnimation", Q_ARG(const QString&, url), Q_ARG(float, fps),
Q_ARG(float, priority), Q_ARG(bool, loop), Q_ARG(bool, hold), Q_ARG(float, firstFrame),
Q_ARG(float, lastFrame), Q_ARG(const QStringList&, maskedJoints));
QMetaObject::invokeMethod(this, "overrideAnimation", Q_ARG(const QString&, url), Q_ARG(float, fps),
Q_ARG(bool, loop), Q_ARG(float, firstFrame), Q_ARG(float, lastFrame));
return;
}
_rig->startAnimation(url, fps, priority, loop, hold, firstFrame, lastFrame, maskedJoints);
_rig->overrideAnimation(url, fps, loop, firstFrame, lastFrame);
}
void MyAvatar::startAnimationByRole(const QString& role, const QString& url, float fps, float priority,
bool loop, bool hold, float firstFrame, float lastFrame, const QStringList& maskedJoints) {
void MyAvatar::restoreAnimation() {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "startAnimationByRole", Q_ARG(const QString&, role), Q_ARG(const QString&, url),
Q_ARG(float, fps), Q_ARG(float, priority), Q_ARG(bool, loop), Q_ARG(bool, hold), Q_ARG(float, firstFrame),
Q_ARG(float, lastFrame), Q_ARG(const QStringList&, maskedJoints));
QMetaObject::invokeMethod(this, "restoreAnimation");
return;
}
_rig->startAnimationByRole(role, url, fps, priority, loop, hold, firstFrame, lastFrame, maskedJoints);
_rig->restoreAnimation();
}
void MyAvatar::stopAnimationByRole(const QString& role) {
QStringList MyAvatar::getAnimationRoles() {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "stopAnimationByRole", Q_ARG(const QString&, role));
return;
}
_rig->stopAnimationByRole(role);
}
void MyAvatar::stopAnimation(const QString& url) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "stopAnimation", Q_ARG(const QString&, url));
return;
}
_rig->stopAnimation(url);
}
AnimationDetails MyAvatar::getAnimationDetailsByRole(const QString& role) {
AnimationDetails result;
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "getAnimationDetailsByRole", Qt::BlockingQueuedConnection,
Q_RETURN_ARG(AnimationDetails, result),
Q_ARG(const QString&, role));
QStringList result;
QMetaObject::invokeMethod(this, "getAnimationRoles", Qt::BlockingQueuedConnection, Q_RETURN_ARG(QStringList, result));
return result;
}
foreach (const AnimationHandlePointer& handle, _rig->getRunningAnimations()) {
if (handle->getRole() == role) {
result = handle->getAnimationDetails();
break;
}
}
return result;
return _rig->getAnimationRoles();
}
AnimationDetails MyAvatar::getAnimationDetails(const QString& url) {
AnimationDetails result;
void MyAvatar::overrideRoleAnimation(const QString& role, const QString& url, float fps, bool loop,
float firstFrame, float lastFrame) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "getAnimationDetails", Qt::BlockingQueuedConnection,
Q_RETURN_ARG(AnimationDetails, result),
Q_ARG(const QString&, url));
return result;
QMetaObject::invokeMethod(this, "overrideRoleAnimation", Q_ARG(const QString&, role), Q_ARG(const QString&, url),
Q_ARG(float, fps), Q_ARG(bool, loop), Q_ARG(float, firstFrame), Q_ARG(float, lastFrame));
return;
}
foreach (const AnimationHandlePointer& handle, _rig->getRunningAnimations()) {
if (handle->getURL() == url) {
result = handle->getAnimationDetails();
break;
}
_rig->overrideRoleAnimation(role, url, fps, loop, firstFrame, lastFrame);
}
void MyAvatar::restoreRoleAnimation(const QString& role) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "restoreRoleAnimation", Q_ARG(const QString&, role));
return;
}
return result;
_rig->restoreRoleAnimation(role);
}
void MyAvatar::prefetchAnimation(const QString& url) {
if (QThread::currentThread() != thread()) {
QMetaObject::invokeMethod(this, "prefetchAnimation", Q_ARG(const QString&, url));
return;
}
_rig->prefetchAnimation(url);
}
void MyAvatar::saveData() {
@ -740,24 +681,6 @@ void MyAvatar::saveData() {
}
settings.endArray();
settings.beginWriteArray("animationHandles");
auto animationHandles = _rig->getAnimationHandles();
for (int i = 0; i < animationHandles.size(); i++) {
settings.setArrayIndex(i);
const AnimationHandlePointer& pointer = animationHandles.at(i);
settings.setValue("role", pointer->getRole());
settings.setValue("url", pointer->getURL());
settings.setValue("fps", pointer->getFPS());
settings.setValue("priority", pointer->getPriority());
settings.setValue("loop", pointer->getLoop());
settings.setValue("hold", pointer->getHold());
settings.setValue("startAutomatically", pointer->getStartAutomatically());
settings.setValue("firstFrame", pointer->getFirstFrame());
settings.setValue("lastFrame", pointer->getLastFrame());
settings.setValue("maskedJoints", pointer->getMaskedJoints());
}
settings.endArray();
settings.setValue("displayName", _displayName);
settings.setValue("collisionSoundURL", _collisionSoundURL);
@ -772,65 +695,11 @@ float loadSetting(QSettings& settings, const char* name, float defaultValue) {
return value;
}
// Resource loading is not yet thread safe. If an animation is not loaded when requested by other than tha main thread,
// we block in AnimationHandle::setURL => AnimationCache::getAnimation.
// Meanwhile, the main thread will also eventually lock as it tries to render us.
// If we demand the animation from the update thread while we're locked, we'll deadlock.
// Until we untangle this, code puts the updates back on the main thread temporarilly and starts all the loading.
void MyAvatar::safelyLoadAnimations() {
_rig->addAnimationByRole("idle");
_rig->addAnimationByRole("walk");
_rig->addAnimationByRole("backup");
_rig->addAnimationByRole("leftTurn");
_rig->addAnimationByRole("rightTurn");
_rig->addAnimationByRole("leftStrafe");
_rig->addAnimationByRole("rightStrafe");
}
void MyAvatar::setEnableRigAnimations(bool isEnabled) {
if (_rig->getEnableRig() == isEnabled) {
return;
}
if (isEnabled) {
qApp->setRawAvatarUpdateThreading(false);
setEnableAnimGraph(false);
Menu::getInstance()->setIsOptionChecked(MenuOption::EnableAnimGraph, false);
safelyLoadAnimations();
qApp->setRawAvatarUpdateThreading();
_rig->setEnableRig(true);
} else {
_rig->setEnableRig(false);
_rig->deleteAnimations();
}
}
void MyAvatar::setEnableAnimGraph(bool isEnabled) {
if (_rig->getEnableAnimGraph() == isEnabled) {
return;
}
if (isEnabled) {
qApp->setRawAvatarUpdateThreading(false);
setEnableRigAnimations(false);
Menu::getInstance()->setIsOptionChecked(MenuOption::EnableRigAnimations, false);
safelyLoadAnimations();
if (_skeletonModel.readyToAddToScene()) {
_rig->setEnableAnimGraph(true);
initAnimGraph(); // must be enabled for the init to happen
_rig->setEnableAnimGraph(false); // must be disable to safely reset threading
}
qApp->setRawAvatarUpdateThreading();
_rig->setEnableAnimGraph(true);
} else {
_rig->setEnableAnimGraph(false);
destroyAnimGraph();
}
}
void MyAvatar::setEnableDebugDrawBindPose(bool isEnabled) {
_enableDebugDrawBindPose = isEnabled;
void MyAvatar::setEnableDebugDrawDefaultPose(bool isEnabled) {
_enableDebugDrawDefaultPose = isEnabled;
if (!isEnabled) {
AnimDebugDraw::getInstance().removeSkeleton("myAvatar");
AnimDebugDraw::getInstance().removeAbsolutePoses("myAvatarDefaultPoses");
}
}
@ -838,7 +707,16 @@ void MyAvatar::setEnableDebugDrawAnimPose(bool isEnabled) {
_enableDebugDrawAnimPose = isEnabled;
if (!isEnabled) {
AnimDebugDraw::getInstance().removePoses("myAvatar");
AnimDebugDraw::getInstance().removeAbsolutePoses("myAvatarAnimPoses");
}
}
void MyAvatar::setEnableDebugDrawPosition(bool isEnabled) {
if (isEnabled) {
const glm::vec4 red(1.0f, 0.0f, 0.0f, 1.0f);
DebugDraw::getInstance().addMyAvatarMarker("avatarPosition", glm::quat(), glm::vec3(), red);
} else {
DebugDraw::getInstance().removeMyAvatarMarker("avatarPosition");
}
}
@ -886,31 +764,15 @@ void MyAvatar::loadData() {
settings.endArray();
setAttachmentData(attachmentData);
int animationCount = settings.beginReadArray("animationHandles");
_rig->deleteAnimations();
for (int i = 0; i < animationCount; i++) {
settings.setArrayIndex(i);
_rig->addAnimationByRole(settings.value("role", "idle").toString(),
settings.value("url").toString(),
loadSetting(settings, "fps", 30.0f),
loadSetting(settings, "priority", 1.0f),
settings.value("loop", true).toBool(),
settings.value("hold", false).toBool(),
settings.value("firstFrame", 0.0f).toFloat(),
settings.value("lastFrame", INT_MAX).toFloat(),
settings.value("maskedJoints").toStringList(),
settings.value("startAutomatically", true).toBool());
}
settings.endArray();
setDisplayName(settings.value("displayName").toString());
setCollisionSoundURL(settings.value("collisionSoundURL", DEFAULT_AVATAR_COLLISION_SOUND_URL).toString());
settings.endGroup();
_rig->setEnableRig(Menu::getInstance()->isOptionChecked(MenuOption::EnableRigAnimations));
setEnableMeshVisible(Menu::getInstance()->isOptionChecked(MenuOption::MeshVisible));
setEnableDebugDrawBindPose(Menu::getInstance()->isOptionChecked(MenuOption::AnimDebugDrawBindPose));
setEnableDebugDrawDefaultPose(Menu::getInstance()->isOptionChecked(MenuOption::AnimDebugDrawDefaultPose));
setEnableDebugDrawAnimPose(Menu::getInstance()->isOptionChecked(MenuOption::AnimDebugDrawAnimPose));
setEnableDebugDrawPosition(Menu::getInstance()->isOptionChecked(MenuOption::AnimDebugDrawPosition));
}
void MyAvatar::saveAttachmentData(const AttachmentData& attachment) const {
@ -1090,11 +952,11 @@ eyeContactTarget MyAvatar::getEyeContactTarget() {
}
glm::vec3 MyAvatar::getDefaultEyePosition() const {
return getPosition() + getWorldAlignedOrientation() * _skeletonModel.getDefaultEyeModelPosition();
return getPosition() + getWorldAlignedOrientation() * Quaternions::Y_180 * _skeletonModel.getDefaultEyeModelPosition();
}
const float SCRIPT_PRIORITY = DEFAULT_PRIORITY + 1.0f;
const float RECORDER_PRIORITY = SCRIPT_PRIORITY + 1.0f;
const float SCRIPT_PRIORITY = 1.0f + 1.0f;
const float RECORDER_PRIORITY = 1.0f + 1.0f;
void MyAvatar::setJointRotations(QVector<glm::quat> jointRotations) {
int numStates = glm::min(_skeletonModel.getJointStateCount(), jointRotations.size());
@ -1143,14 +1005,7 @@ void MyAvatar::clearJointData(int index) {
}
void MyAvatar::clearJointsData() {
clearJointAnimationPriorities();
}
void MyAvatar::clearJointAnimationPriorities() {
int numStates = _skeletonModel.getJointStateCount();
for (int i = 0; i < numStates; ++i) {
_rig->clearJointAnimationPriority(i);
}
//clearJointAnimationPriorities();
}
void MyAvatar::setFaceModelURL(const QUrl& faceModelURL) {
@ -1195,16 +1050,8 @@ void MyAvatar::useFullAvatarURL(const QUrl& fullAvatarURL, const QString& modelN
const QString& urlString = fullAvatarURL.toString();
if (urlString.isEmpty() || (fullAvatarURL != getSkeletonModelURL())) {
bool isRigEnabled = getEnableRigAnimations();
bool isGraphEnabled = getEnableAnimGraph();
qApp->setRawAvatarUpdateThreading(false);
setEnableRigAnimations(false);
setEnableAnimGraph(false);
setSkeletonModelURL(fullAvatarURL);
setEnableRigAnimations(isRigEnabled);
setEnableAnimGraph(isGraphEnabled);
qApp->setRawAvatarUpdateThreading();
UserActivityLogger::getInstance().changedModel("skeleton", urlString);
}
@ -1340,7 +1187,6 @@ void MyAvatar::setScriptedMotorFrame(QString frame) {
}
void MyAvatar::clearScriptableSettings() {
clearJointAnimationPriorities();
_scriptedMotorVelocity = glm::vec3(0.0f);
_scriptedMotorTimescale = DEFAULT_SCRIPTED_MOTOR_TIMESCALE;
}
@ -1459,7 +1305,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);
_bodySensorMatrix = deriveBodyFromHMDSensor(); // Based on current cached HMD position/rotation..
updateSensorToWorldMatrix(); // Uses updated position/orientation and _bodySensorMatrix changes
@ -1478,38 +1324,29 @@ void MyAvatar::preRender(RenderArgs* renderArgs) {
initHeadBones();
_skeletonModel.setCauterizeBoneSet(_headBoneSet);
initAnimGraph();
_debugDrawSkeleton = std::make_shared<AnimSkeleton>(_skeletonModel.getGeometry()->getFBXGeometry());
}
if (_enableDebugDrawBindPose || _enableDebugDrawAnimPose) {
if (_enableDebugDrawDefaultPose || _enableDebugDrawAnimPose) {
// bones are aligned such that z is forward, not -z.
glm::quat rotY180 = glm::angleAxis((float)M_PI, glm::vec3(0.0f, 1.0f, 0.0f));
AnimPose xform(glm::vec3(1), getOrientation() * rotY180, getPosition());
auto animSkeleton = _rig->getAnimSkeleton();
if (_enableDebugDrawBindPose && _debugDrawSkeleton) {
// the rig is in the skeletonModel frame
AnimPose xform(glm::vec3(1), _skeletonModel.getRotation(), _skeletonModel.getTranslation());
if (_enableDebugDrawDefaultPose && animSkeleton) {
glm::vec4 gray(0.2f, 0.2f, 0.2f, 0.2f);
AnimDebugDraw::getInstance().addSkeleton("myAvatar", _debugDrawSkeleton, xform, gray);
AnimDebugDraw::getInstance().addAbsolutePoses("myAvatarDefaultPoses", animSkeleton, _rig->getAbsoluteDefaultPoses(), xform, gray);
}
if (_enableDebugDrawAnimPose && _debugDrawSkeleton) {
glm::vec4 cyan(0.1f, 0.6f, 0.6f, 1.0f);
// build AnimPoseVec from JointStates.
AnimPoseVec poses;
poses.reserve(_debugDrawSkeleton->getNumJoints());
for (int i = 0; i < _debugDrawSkeleton->getNumJoints(); i++) {
AnimPose pose = _debugDrawSkeleton->getRelativeBindPose(i);
glm::quat jointRot;
_rig->getJointRotationInConstrainedFrame(i, jointRot);
glm::vec3 jointTrans;
_rig->getJointTranslation(i, jointTrans);
pose.rot = pose.rot * jointRot;
pose.trans = jointTrans;
poses.push_back(pose);
if (_enableDebugDrawAnimPose && animSkeleton) {
// build absolute AnimPoseVec from rig
AnimPoseVec absPoses;
absPoses.reserve(_rig->getJointStateCount());
for (int i = 0; i < _rig->getJointStateCount(); i++) {
absPoses.push_back(AnimPose(_rig->getJointTransform(i)));
}
AnimDebugDraw::getInstance().addPoses("myAvatar", _debugDrawSkeleton, poses, xform, cyan);
glm::vec4 cyan(0.1f, 0.6f, 0.6f, 1.0f);
AnimDebugDraw::getInstance().addAbsolutePoses("myAvatarAnimPoses", animSkeleton, absPoses, xform, cyan);
}
}
@ -1961,54 +1798,33 @@ glm::mat4 MyAvatar::deriveBodyFromHMDSensor() const {
const glm::quat hmdOrientation = getHMDSensorOrientation();
const glm::quat hmdOrientationYawOnly = cancelOutRollAndPitch(hmdOrientation);
/*
const glm::vec3 DEFAULT_RIGHT_EYE_POS(-0.3f, 1.6f, 0.0f);
const glm::vec3 DEFAULT_LEFT_EYE_POS(0.3f, 1.6f, 0.0f);
const glm::vec3 DEFAULT_NECK_POS(0.0f, 1.5f, 0.0f);
const glm::vec3 DEFAULT_HIPS_POS(0.0f, 1.0f, 0.0f);
*/
// 2 meter tall dude (in rig coordinates)
const glm::vec3 DEFAULT_RIG_MIDDLE_EYE_POS(0.0f, 0.9f, 0.0f);
const glm::vec3 DEFAULT_RIG_NECK_POS(0.0f, 0.70f, 0.0f);
const glm::vec3 DEFAULT_RIG_HIPS_POS(0.0f, 0.05f, 0.0f);
// 2 meter tall dude
const glm::vec3 DEFAULT_RIGHT_EYE_POS(-0.3f, 1.9f, 0.0f);
const glm::vec3 DEFAULT_LEFT_EYE_POS(0.3f, 1.9f, 0.0f);
const glm::vec3 DEFAULT_NECK_POS(0.0f, 1.70f, 0.0f);
const glm::vec3 DEFAULT_HIPS_POS(0.0f, 1.05f, 0.0f);
int rightEyeIndex = _rig->indexOfJoint("RightEye");
int leftEyeIndex = _rig->indexOfJoint("LeftEye");
int neckIndex = _rig->indexOfJoint("Neck");
int hipsIndex = _rig->indexOfJoint("Hips");
vec3 localEyes, localNeck;
if (!_debugDrawSkeleton) {
const glm::quat rotY180 = glm::angleAxis((float)PI, glm::vec3(0.0f, 1.0f, 0.0f));
localEyes = rotY180 * (((DEFAULT_RIGHT_EYE_POS + DEFAULT_LEFT_EYE_POS) / 2.0f) - DEFAULT_HIPS_POS);
localNeck = rotY180 * (DEFAULT_NECK_POS - DEFAULT_HIPS_POS);
} else {
// TODO: At the moment MyAvatar does not have access to the rig, which has the skeleton, which has the bind poses.
// for now use the _debugDrawSkeleton, which is initialized with the same FBX model as the rig.
glm::vec3 rigMiddleEyePos = leftEyeIndex != -1 ? _rig->getAbsoluteDefaultPose(leftEyeIndex).trans : DEFAULT_RIG_MIDDLE_EYE_POS;
glm::vec3 rigNeckPos = neckIndex != -1 ? _rig->getAbsoluteDefaultPose(neckIndex).trans : DEFAULT_RIG_NECK_POS;
glm::vec3 rigHipsPos = hipsIndex != -1 ? _rig->getAbsoluteDefaultPose(hipsIndex).trans : DEFAULT_RIG_HIPS_POS;
// TODO: cache these indices.
int rightEyeIndex = _debugDrawSkeleton->nameToJointIndex("RightEye");
int leftEyeIndex = _debugDrawSkeleton->nameToJointIndex("LeftEye");
int neckIndex = _debugDrawSkeleton->nameToJointIndex("Neck");
int hipsIndex = _debugDrawSkeleton->nameToJointIndex("Hips");
glm::vec3 absRightEyePos = rightEyeIndex != -1 ? _debugDrawSkeleton->getAbsoluteBindPose(rightEyeIndex).trans : DEFAULT_RIGHT_EYE_POS;
glm::vec3 absLeftEyePos = leftEyeIndex != -1 ? _debugDrawSkeleton->getAbsoluteBindPose(leftEyeIndex).trans : DEFAULT_LEFT_EYE_POS;
glm::vec3 absNeckPos = neckIndex != -1 ? _debugDrawSkeleton->getAbsoluteBindPose(neckIndex).trans : DEFAULT_NECK_POS;
glm::vec3 absHipsPos = neckIndex != -1 ? _debugDrawSkeleton->getAbsoluteBindPose(hipsIndex).trans : DEFAULT_HIPS_POS;
const glm::quat rotY180 = glm::angleAxis((float)PI, glm::vec3(0.0f, 1.0f, 0.0f));
localEyes = rotY180 * (((absRightEyePos + absLeftEyePos) / 2.0f) - absHipsPos);
localNeck = rotY180 * (absNeckPos - absHipsPos);
}
glm::vec3 localEyes = (rigMiddleEyePos - rigHipsPos);
glm::vec3 localNeck = (rigNeckPos - rigHipsPos);
// apply simplistic head/neck model
// figure out where the avatar body should be by applying offsets from the avatar's neck & head joints.
// eyeToNeck offset is relative full HMD orientation.
// while neckToRoot offset is only relative to HMDs yaw.
glm::vec3 eyeToNeck = hmdOrientation * (localNeck - localEyes);
glm::vec3 neckToRoot = hmdOrientationYawOnly * -localNeck;
// Y_180 is necessary because rig is z forward and hmdOrientation is -z forward
glm::vec3 eyeToNeck = hmdOrientation * Quaternions::Y_180 * (localNeck - localEyes);
glm::vec3 neckToRoot = hmdOrientationYawOnly * Quaternions::Y_180 * -localNeck;
glm::vec3 bodyPos = hmdPosition + eyeToNeck + neckToRoot;
// avatar facing is determined solely by hmd orientation.
return createMatFromQuatAndPos(hmdOrientationYawOnly, bodyPos);
}
#endif

View file

@ -114,27 +114,24 @@ public:
float getRealWorldFieldOfView() { return _realWorldFieldOfView.get(); }
const QList<AnimationHandlePointer>& getAnimationHandles() const { return _rig->getAnimationHandles(); }
AnimationHandlePointer addAnimationHandle() { return _rig->createAnimationHandle(); }
void removeAnimationHandle(const AnimationHandlePointer& handle) { _rig->removeAnimationHandle(handle); }
/// Allows scripts to run animations.
Q_INVOKABLE void startAnimation(const QString& url, float fps = 30.0f, float priority = 1.0f, bool loop = false,
bool hold = false, float firstFrame = 0.0f,
float lastFrame = FLT_MAX, const QStringList& maskedJoints = QStringList());
// Interrupt the current animation with a custom animation.
Q_INVOKABLE void overrideAnimation(const QString& url, float fps, bool loop, float firstFrame, float lastFrame);
/// Stops an animation as identified by a URL.
Q_INVOKABLE void stopAnimation(const QString& url);
// Stop the animation that was started with overrideAnimation and go back to the standard animation.
Q_INVOKABLE void restoreAnimation();
// Returns a list of all clips that are available
Q_INVOKABLE QStringList getAnimationRoles();
// Replace an existing standard role animation with a custom one.
Q_INVOKABLE void overrideRoleAnimation(const QString& role, const QString& url, float fps, bool loop, float firstFrame, float lastFrame);
// remove an animation role override and return to the standard animation.
Q_INVOKABLE void restoreRoleAnimation(const QString& role);
// prefetch animation
Q_INVOKABLE void prefetchAnimation(const QString& url);
/// Starts an animation by its role, using the provided URL and parameters if the avatar doesn't have a custom
/// animation for the role.
Q_INVOKABLE void startAnimationByRole(const QString& role, const QString& url = QString(), float fps = 30.0f,
float priority = 1.0f, bool loop = false, bool hold = false, float firstFrame = 0.0f,
float lastFrame = FLT_MAX, const QStringList& maskedJoints = QStringList());
/// Stops an animation identified by its role.
Q_INVOKABLE void stopAnimationByRole(const QString& role);
Q_INVOKABLE AnimationDetails getAnimationDetailsByRole(const QString& role);
Q_INVOKABLE AnimationDetails getAnimationDetails(const QString& url);
void clearJointAnimationPriorities();
// Adds handler(animStateDictionaryIn) => animStateDictionaryOut, which will be invoked just before each animGraph state update.
// The handler will be called with an animStateDictionaryIn that has all those properties specified by the (possibly empty)
// propertiesList argument. However for debugging, if the properties argument is null, all internal animGraph state is provided.
@ -256,13 +253,11 @@ public slots:
virtual void rebuildSkeletonBody() override;
bool getEnableRigAnimations() const { return _rig->getEnableRig(); }
void setEnableRigAnimations(bool isEnabled);
bool getEnableAnimGraph() const { return _rig->getEnableAnimGraph(); }
const QString& getAnimGraphUrl() const { return _animGraphUrl; }
void setEnableAnimGraph(bool isEnabled);
void setEnableDebugDrawBindPose(bool isEnabled);
void setEnableDebugDrawDefaultPose(bool isEnabled);
void setEnableDebugDrawAnimPose(bool isEnabled);
void setEnableDebugDrawPosition(bool isEnabled);
void setEnableMeshVisible(bool isEnabled);
void setAnimGraphUrl(const QString& url) { _animGraphUrl = url; }
@ -361,7 +356,6 @@ private:
void maybeUpdateBillboard();
void initHeadBones();
void initAnimGraph();
void safelyLoadAnimations();
// Avatar Preferences
QUrl _fullAvatarURLFromPreferences;
@ -393,9 +387,8 @@ private:
RigPointer _rig;
bool _prevShouldDrawHead;
bool _enableDebugDrawBindPose { false };
bool _enableDebugDrawDefaultPose { false };
bool _enableDebugDrawAnimPose { false };
AnimSkeleton::ConstPointer _debugDrawSkeleton { nullptr };
AudioListenerMode _audioListenerMode;
glm::vec3 _customListenPosition;

View file

@ -26,7 +26,6 @@
SkeletonModel::SkeletonModel(Avatar* owningAvatar, QObject* parent, RigPointer rig) :
Model(rig, parent),
_triangleFanID(DependencyManager::get<GeometryCache>()->allocateID()),
_owningAvatar(owningAvatar),
_boundingCapsuleLocalOffset(0.0f),
_boundingCapsuleRadius(0.0f),
@ -41,26 +40,11 @@ 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;
int rootJointIndex = geometry.rootJointIndex;
int leftHandJointIndex = geometry.leftHandJointIndex;
int leftElbowJointIndex = leftHandJointIndex >= 0 ? geometry.joints.at(leftHandJointIndex).parentIndex : -1;
int leftShoulderJointIndex = leftElbowJointIndex >= 0 ? geometry.joints.at(leftElbowJointIndex).parentIndex : -1;
int rightHandJointIndex = geometry.rightHandJointIndex;
int rightElbowJointIndex = rightHandJointIndex >= 0 ? geometry.joints.at(rightHandJointIndex).parentIndex : -1;
int rightShoulderJointIndex = rightElbowJointIndex >= 0 ? geometry.joints.at(rightElbowJointIndex).parentIndex : -1;
_rig->initJointStates(states, rootTransform,
rootJointIndex,
leftHandJointIndex,
leftElbowJointIndex,
leftShoulderJointIndex,
rightHandJointIndex,
rightElbowJointIndex,
rightShoulderJointIndex);
glm::mat4 geometryOffset = geometry.offset;
glm::mat4 modelOffset = glm::scale(_scale) * glm::translate(_offset);
_rig->initJointStates(geometry, modelOffset);
// Determine the default eye position for avatar scale = 1.0
int headJointIndex = _geometry->getFBXGeometry().headJointIndex;
@ -75,19 +59,11 @@ void SkeletonModel::initJointStates(QVector<JointState> states) {
getJointPosition(rootJointIndex, rootModelPosition);
_defaultEyeModelPosition = midEyePosition - rootModelPosition;
_defaultEyeModelPosition.z = -_defaultEyeModelPosition.z;
// Skeleton may have already been scaled so unscale it
_defaultEyeModelPosition = _defaultEyeModelPosition / _scale;
}
// 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();
Extents meshExtents = getMeshExtents();
@ -98,7 +74,6 @@ void SkeletonModel::initJointStates(QVector<JointState> states) {
emit skeletonLoaded();
}
const float PALM_PRIORITY = DEFAULT_PRIORITY;
// Called within Model::simulate call, below.
void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
Head* head = _owningAvatar->getHead();
@ -111,32 +86,24 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
headParams.leanSideways = head->getFinalLeanSideways();
headParams.leanForward = head->getFinalLeanForward();
headParams.torsoTwist = head->getTorsoTwist();
headParams.localHeadPitch = head->getFinalPitch();
headParams.localHeadYaw = head->getFinalYaw();
headParams.localHeadRoll = head->getFinalRoll();
if (qApp->getAvatarUpdater()->isHMDMode()) {
headParams.isInHMD = true;
// get HMD position from sensor space into world space, and back into model space
AnimPose avatarToWorld(glm::vec3(1.0f), myAvatar->getOrientation(), myAvatar->getPosition());
glm::mat4 worldToAvatar = glm::inverse((glm::mat4)avatarToWorld);
// get HMD position from sensor space into world space, and back into rig space
glm::mat4 worldHMDMat = myAvatar->getSensorToWorldMatrix() * myAvatar->getHMDSensorMatrix();
glm::mat4 hmdMat = worldToAvatar * worldHMDMat;
// in local avatar space (i.e. relative to avatar pos/orientation.)
glm::vec3 hmdPosition = extractTranslation(hmdMat);
glm::quat hmdOrientation = extractRotation(hmdMat);
headParams.localHeadPosition = hmdPosition;
headParams.localHeadOrientation = hmdOrientation;
glm::mat4 rigToWorld = createMatFromQuatAndPos(getRotation(), getTranslation());
glm::mat4 worldToRig = glm::inverse(rigToWorld);
glm::mat4 rigHMDMat = worldToRig * worldHMDMat;
headParams.rigHeadPosition = extractTranslation(rigHMDMat);
headParams.rigHeadOrientation = extractRotation(rigHMDMat);
headParams.worldHeadOrientation = extractRotation(worldHMDMat);
} else {
headParams.isInHMD = false;
// We don't have a valid localHeadPosition.
headParams.localHeadOrientation = head->getFinalOrientationInLocalFrame();
headParams.rigHeadOrientation = Quaternions::Y_180 * head->getFinalOrientationInLocalFrame();
headParams.worldHeadOrientation = head->getFinalOrientationInWorldFrame();
}
@ -151,8 +118,8 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
auto leftPalm = myAvatar->getHand()->getCopyOfPalmData(HandData::LeftHand);
if (leftPalm.isValid() && leftPalm.isActive()) {
handParams.isLeftEnabled = true;
handParams.leftPosition = leftPalm.getRawPosition();
handParams.leftOrientation = leftPalm.getRawRotation();
handParams.leftPosition = Quaternions::Y_180 * leftPalm.getRawPosition();
handParams.leftOrientation = Quaternions::Y_180 * leftPalm.getRawRotation();
handParams.leftTrigger = leftPalm.getTrigger();
} else {
handParams.isLeftEnabled = false;
@ -161,8 +128,8 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
auto rightPalm = myAvatar->getHand()->getCopyOfPalmData(HandData::RightHand);
if (rightPalm.isValid() && rightPalm.isActive()) {
handParams.isRightEnabled = true;
handParams.rightPosition = rightPalm.getRawPosition();
handParams.rightOrientation = rightPalm.getRawRotation();
handParams.rightPosition = Quaternions::Y_180 * rightPalm.getRawPosition();
handParams.rightOrientation = Quaternions::Y_180 * rightPalm.getRawRotation();
handParams.rightTrigger = rightPalm.getTrigger();
} else {
handParams.isRightEnabled = false;
@ -171,6 +138,7 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
_rig->updateFromHandParameters(handParams, deltaTime);
_rig->computeMotionAnimationState(deltaTime, _owningAvatar->getPosition(), _owningAvatar->getVelocity(), _owningAvatar->getOrientation());
// evaluate AnimGraph animation and update jointStates.
Model::updateRig(deltaTime, parentTransform);
@ -185,10 +153,6 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
_rig->updateFromEyeParameters(eyeParams);
// 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);
@ -202,6 +166,7 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
// However, in the !isLookingAtMe case, the eyes aren't rotating the way they should right now.
// We will revisit that as priorities allow, and particularly after the new rig/animation/joints.
const FBXGeometry& geometry = _geometry->getFBXGeometry();
// If the head is not positioned, updateEyeJoints won't get the math right
glm::quat headOrientation;
_rig->getJointRotation(geometry.headJointIndex, headOrientation);
@ -218,14 +183,14 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
eyeParams.modelTranslation = getTranslation();
eyeParams.leftEyeJointIndex = geometry.leftEyeJointIndex;
eyeParams.rightEyeJointIndex = geometry.rightEyeJointIndex;
_rig->updateFromEyeParameters(eyeParams);
}
}
void SkeletonModel::updateAttitude() {
setTranslation(_owningAvatar->getSkeletonPosition());
static const glm::quat refOrientation = glm::angleAxis(PI, glm::vec3(0.0f, 1.0f, 0.0f));
setRotation(_owningAvatar->getOrientation() * refOrientation);
setRotation(_owningAvatar->getOrientation() * Quaternions::Y_180);
setScale(glm::vec3(1.0f, 1.0f, 1.0f) * _owningAvatar->getScale());
}
@ -238,9 +203,9 @@ void SkeletonModel::simulate(float deltaTime, bool fullUpdate) {
Model::simulate(deltaTime, fullUpdate);
// let rig compute the model offset
glm::vec3 modelOffset;
if (_rig->getModelOffset(modelOffset)) {
setOffset(modelOffset);
glm::vec3 registrationPoint;
if (_rig->getModelRegistrationPoint(registrationPoint)) {
setOffset(registrationPoint);
}
if (!isActive() || !_owningAvatar->isMyAvatar()) {
@ -251,45 +216,6 @@ void SkeletonModel::simulate(float deltaTime, bool fullUpdate) {
if (player->isPlaying()) {
return;
}
const FBXGeometry& geometry = _geometry->getFBXGeometry();
// Don't Relax toward hand positions when in animGraph mode.
if (!_rig->getEnableAnimGraph()) {
Hand* hand = _owningAvatar->getHand();
auto leftPalm = hand->getCopyOfPalmData(HandData::LeftHand);
auto rightPalm = hand->getCopyOfPalmData(HandData::RightHand);
const float HAND_RESTORATION_RATE = 0.25f;
if (!leftPalm.isActive() && !rightPalm.isActive()) {
// palms are not yet set, use mouse
if (_owningAvatar->getHandState() == HAND_STATE_NULL) {
restoreRightHandPosition(HAND_RESTORATION_RATE, PALM_PRIORITY);
} else {
// transform into model-frame
glm::vec3 handPosition = glm::inverse(_rotation) * (_owningAvatar->getHandPosition() - _translation);
applyHandPosition(geometry.rightHandJointIndex, handPosition);
}
restoreLeftHandPosition(HAND_RESTORATION_RATE, PALM_PRIORITY);
} else {
if (leftPalm.isActive()) {
applyPalmData(geometry.leftHandJointIndex, leftPalm);
} else {
restoreLeftHandPosition(HAND_RESTORATION_RATE, PALM_PRIORITY);
}
if (rightPalm.isActive()) {
applyPalmData(geometry.rightHandJointIndex, rightPalm);
} else {
restoreRightHandPosition(HAND_RESTORATION_RATE, PALM_PRIORITY);
}
}
}
}
void SkeletonModel::renderIKConstraints(gpu::Batch& batch) {
renderJointConstraints(batch, getRightHandJointIndex());
renderJointConstraints(batch, getLeftHandJointIndex());
}
class IndexValue {
@ -302,34 +228,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;
@ -344,100 +242,6 @@ void SkeletonModel::applyPalmData(int jointIndex, const PalmData& palm) {
glm::quat inverseRotation = glm::inverse(_rotation);
glm::vec3 palmPosition = inverseRotation * (palm.getPosition() - _translation);
glm::quat palmRotation = inverseRotation * palm.getRotation();
inverseKinematics(jointIndex, palmPosition, palmRotation, PALM_PRIORITY);
}
void SkeletonModel::renderJointConstraints(gpu::Batch& batch, int jointIndex) {
if (jointIndex == -1 || jointIndex >= _rig->getJointStateCount()) {
return;
}
const FBXGeometry& geometry = _geometry->getFBXGeometry();
const float BASE_DIRECTION_SIZE = 0.3f;
float directionSize = BASE_DIRECTION_SIZE * extractUniformScale(_scale);
// FIXME: THe line width of 3.0f is not supported anymore, we ll need a workaround
do {
const FBXJoint& joint = geometry.joints.at(jointIndex);
const JointState& jointState = _rig->getJointState(jointIndex);
glm::vec3 position = _rotation * jointState.getPosition() + _translation;
glm::quat parentRotation = (joint.parentIndex == -1) ?
_rotation :
_rotation * _rig->getJointState(joint.parentIndex).getRotation();
float fanScale = directionSize * 0.75f;
Transform transform = Transform();
transform.setTranslation(position);
transform.setRotation(parentRotation);
transform.setScale(fanScale);
batch.setModelTransform(transform);
const int AXIS_COUNT = 3;
auto geometryCache = DependencyManager::get<GeometryCache>();
for (int i = 0; i < AXIS_COUNT; i++) {
if (joint.rotationMin[i] <= -PI + EPSILON && joint.rotationMax[i] >= PI - EPSILON) {
continue; // unconstrained
}
glm::vec3 axis;
axis[i] = 1.0f;
glm::vec3 otherAxis;
if (i == 0) {
otherAxis.y = 1.0f;
} else {
otherAxis.x = 1.0f;
}
glm::vec4 color(otherAxis.r, otherAxis.g, otherAxis.b, 0.75f);
QVector<glm::vec3> points;
points << glm::vec3(0.0f, 0.0f, 0.0f);
const int FAN_SEGMENTS = 16;
for (int j = 0; j < FAN_SEGMENTS; j++) {
glm::vec3 rotated = glm::angleAxis(glm::mix(joint.rotationMin[i], joint.rotationMax[i],
(float)j / (FAN_SEGMENTS - 1)), axis) * otherAxis;
points << rotated;
}
// TODO: this is really inefficient constantly recreating these vertices buffers. It would be
// better if the skeleton model cached these buffers for each of the joints they are rendering
geometryCache->updateVertices(_triangleFanID, points, color);
geometryCache->renderVertices(batch, gpu::TRIANGLE_FAN, _triangleFanID);
}
renderOrientationDirections(batch, jointIndex, position, _rotation * jointState.getRotation(), directionSize);
jointIndex = joint.parentIndex;
} while (jointIndex != -1 && geometry.joints.at(jointIndex).isFree);
}
void SkeletonModel::renderOrientationDirections(gpu::Batch& batch, int jointIndex,
glm::vec3 position, const glm::quat& orientation, float size) {
auto geometryCache = DependencyManager::get<GeometryCache>();
if (!_jointOrientationLines.contains(jointIndex)) {
OrientationLineIDs jointLineIDs;
jointLineIDs._up = geometryCache->allocateID();
jointLineIDs._front = geometryCache->allocateID();
jointLineIDs._right = geometryCache->allocateID();
_jointOrientationLines[jointIndex] = jointLineIDs;
}
OrientationLineIDs& jointLineIDs = _jointOrientationLines[jointIndex];
glm::vec3 pRight = position + orientation * IDENTITY_RIGHT * size;
glm::vec3 pUp = position + orientation * IDENTITY_UP * size;
glm::vec3 pFront = position + orientation * IDENTITY_FRONT * size;
glm::vec3 red(1.0f, 0.0f, 0.0f);
geometryCache->renderLine(batch, position, pRight, red, jointLineIDs._right);
glm::vec3 green(0.0f, 1.0f, 0.0f);
geometryCache->renderLine(batch, position, pUp, green, jointLineIDs._up);
glm::vec3 blue(0.0f, 0.0f, 1.0f);
geometryCache->renderLine(batch, position, pFront, blue, jointLineIDs._front);
}
bool SkeletonModel::getLeftHandPosition(glm::vec3& position) const {
@ -484,27 +288,10 @@ bool SkeletonModel::getLocalNeckPosition(glm::vec3& neckPosition) const {
return isActive() && getJointPosition(_geometry->getFBXGeometry().neckJointIndex, neckPosition);
}
bool SkeletonModel::getNeckParentRotationFromDefaultOrientation(glm::quat& neckParentRotation) const {
if (!isActive()) {
return false;
}
const FBXGeometry& geometry = _geometry->getFBXGeometry();
if (geometry.neckJointIndex == -1) {
return false;
}
int parentIndex = geometry.joints.at(geometry.neckJointIndex).parentIndex;
glm::quat worldFrameRotation;
bool success = getJointRotationInWorldFrame(parentIndex, worldFrameRotation);
if (success) {
neckParentRotation = worldFrameRotation * _rig->getJointState(parentIndex).getInverseDefaultRotation();
}
return success;
}
bool SkeletonModel::getEyeModelPositions(glm::vec3& firstEyePosition, glm::vec3& secondEyePosition) const {
if (!isActive()) {
return false;
}
}
const FBXGeometry& geometry = _geometry->getFBXGeometry();
if (getJointPosition(geometry.leftEyeJointIndex, firstEyePosition) &&
getJointPosition(geometry.rightEyeJointIndex, secondEyePosition)) {
@ -557,112 +344,17 @@ void SkeletonModel::computeBoundingShape() {
return;
}
// 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.
// Measure limb lengths so we can specify IK targets that will pull hands and feet tight to body
QVector<QString> endEffectors;
endEffectors.push_back("RightHand");
endEffectors.push_back("LeftHand");
endEffectors.push_back("RightFoot");
endEffectors.push_back("LeftFoot");
QVector<QString> baseJoints;
baseJoints.push_back("RightArm");
baseJoints.push_back("LeftArm");
baseJoints.push_back("RightUpLeg");
baseJoints.push_back("LeftUpLeg");
for (int i = 0; i < endEffectors.size(); ++i) {
QString tipName = endEffectors[i];
QString baseName = baseJoints[i];
float limbLength = 0.0f;
int tipIndex = _rig->indexOfJoint(tipName);
if (tipIndex == -1) {
continue;
}
// save tip's relative rotation for later
glm::quat tipRotation = _rig->getJointState(tipIndex).getRotationInConstrainedFrame();
// IK on each endpoint
int jointIndex = tipIndex;
QVector<int> freeLineage;
float priority = 1.0f;
while (jointIndex > -1) {
JointState limbJoint = _rig->getJointState(jointIndex);
freeLineage.push_back(jointIndex);
if (limbJoint.getName() == baseName) {
glm::vec3 targetPosition = limbJoint.getPosition() - glm::vec3(0.0f, 1.5f * limbLength, 0.0f);
// do IK a few times to make sure the endpoint gets close to its target
for (int j = 0; j < 5; ++j) {
_rig->inverseKinematics(tipIndex,
targetPosition,
glm::quat(),
priority,
freeLineage,
glm::mat4());
}
break;
}
limbLength += limbJoint.getDistanceToParent();
jointIndex = limbJoint.getParentIndex();
}
// since this IK target is totally bogus we restore the tip's relative rotation
_rig->setJointRotationInConstrainedFrame(tipIndex, tipRotation, priority);
}
// recompute all joint model-frame transforms
glm::mat4 rootTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
for (int i = 0; i < _rig->getJointStateCount(); i++) {
_rig->updateJointState(i, rootTransform);
}
// END BOUNDING SHAPE HACK
// compute bounding box that encloses all shapes
Extents totalExtents;
totalExtents.reset();
totalExtents.addPoint(glm::vec3(0.0f));
int numStates = _rig->getJointStateCount();
for (int i = 0; i < numStates; i++) {
// Each joint contributes a capsule defined by FBXJoint.shapeInfo.
// For totalExtents we use the capsule endpoints expanded by the radius.
const JointState& state = _rig->getJointState(i);
const glm::mat4& jointTransform = state.getTransform();
const FBXJointShapeInfo& shapeInfo = geometry.joints.at(i).shapeInfo;
if (shapeInfo.points.size() > 0) {
for (int j = 0; j < shapeInfo.points.size(); ++j) {
totalExtents.addPoint(extractTranslation(jointTransform * glm::translate(shapeInfo.points[j])));
}
}
// HACK so that default legless robot doesn't knuckle-drag
if (shapeInfo.points.size() == 0 && (state.getName() == "LeftFoot" || state.getName() == "RightFoot")) {
totalExtents.addPoint(extractTranslation(jointTransform));
}
}
// compute bounding shape parameters
// NOTE: we assume that the longest side of totalExtents is the yAxis...
glm::vec3 diagonal = totalExtents.maximum - totalExtents.minimum;
// ... and assume the radius is half the RMS of the X and Z sides:
_boundingCapsuleRadius = 0.5f * sqrtf(0.5f * (diagonal.x * diagonal.x + diagonal.z * diagonal.z));
_boundingCapsuleHeight = diagonal.y - 2.0f * _boundingCapsuleRadius;
glm::vec3 rootPosition = _rig->getJointState(geometry.rootJointIndex).getPosition();
_boundingCapsuleLocalOffset = 0.5f * (totalExtents.maximum + totalExtents.minimum) - rootPosition;
// RECOVER FROM BOUNINDG SHAPE HACK: now that we're all done, restore the default pose
for (int i = 0; i < numStates; i++) {
_rig->restoreJointRotation(i, 1.0f, 1.0f);
_rig->restoreJointTranslation(i, 1.0f, 1.0f);
}
_rig->computeAvatarBoundingCapsule(geometry,
_boundingCapsuleRadius,
_boundingCapsuleHeight,
_boundingCapsuleLocalOffset);
}
void SkeletonModel::renderBoundingCollisionShapes(gpu::Batch& batch, float alpha) {
auto geometryCache = DependencyManager::get<GeometryCache>();
auto deferredLighting = DependencyManager::get<DeferredLightingEffect>();
// draw a blue sphere at the capsule top point
glm::vec3 topPoint = _translation + _boundingCapsuleLocalOffset + (0.5f * _boundingCapsuleHeight) * glm::vec3(0.0f, 1.0f, 0.0f);
glm::vec3 topPoint = _translation + getRotation() * (_boundingCapsuleLocalOffset + (0.5f * _boundingCapsuleHeight) * glm::vec3(0.0f, 1.0f, 0.0f));
deferredLighting->renderSolidSphereInstance(batch,
Transform().setTranslation(topPoint).postScale(_boundingCapsuleRadius),

View file

@ -27,14 +27,12 @@ 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;
void updateAttitude();
void renderIKConstraints(gpu::Batch& batch);
/// Returns the index of the left hand joint, or -1 if not found.
int getLeftHandJointIndex() const { return isActive() ? _geometry->getFBXGeometry().leftHandJointIndex : -1; }
@ -83,10 +81,6 @@ public:
bool getLocalNeckPosition(glm::vec3& neckPosition) const;
/// Returns the rotation of the neck joint's parent from default orientation
/// \return whether or not the neck was found
bool getNeckParentRotationFromDefaultOrientation(glm::quat& neckParentRotation) const;
/// Retrieve the positions of up to two eye meshes.
/// \return whether or not both eye meshes were found
bool getEyePositions(glm::vec3& firstEyePosition, glm::vec3& secondEyePosition) const;
@ -114,25 +108,9 @@ 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:
void renderJointConstraints(gpu::Batch& batch, int jointIndex);
void renderOrientationDirections(gpu::Batch& batch, int jointIndex,
glm::vec3 position, const glm::quat& orientation, float size);
struct OrientationLineIDs {
int _up;
int _front;
int _right;
};
QHash<int, OrientationLineIDs> _jointOrientationLines;
int _triangleFanID;
bool getEyeModelPositions(glm::vec3& firstEyePosition, glm::vec3& secondEyePosition) const;
Avatar* _owningAvatar;

View file

@ -1,210 +0,0 @@
//
// AnimationsDialog.cpp
// interface/src/ui
//
// Created by Andrzej Kapolka on 5/19/14.
// Copyright 2014 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#include <QCheckBox>
#include <QComboBox>
#include <QDialogButtonBox>
#include <QDoubleSpinBox>
#include <QFileDialog>
#include <QFormLayout>
#include <QLineEdit>
#include <QMenu>
#include <QPushButton>
#include <QScrollArea>
#include <QVBoxLayout>
#include "avatar/AvatarManager.h"
#include "AnimationsDialog.h"
AnimationsDialog::AnimationsDialog(QWidget* parent) :
QDialog(parent)
{
setWindowTitle("Edit Animations");
setAttribute(Qt::WA_DeleteOnClose);
QVBoxLayout* layout = new QVBoxLayout();
setLayout(layout);
QScrollArea* area = new QScrollArea();
layout->addWidget(area);
area->setWidgetResizable(true);
QWidget* container = new QWidget();
container->setLayout(_animations = new QVBoxLayout());
container->setSizePolicy(QSizePolicy::Ignored, QSizePolicy::Preferred);
area->setWidget(container);
_animations->addStretch(1);
MyAvatar* myAvatar = DependencyManager::get<AvatarManager>()->getMyAvatar();
foreach (const AnimationHandlePointer& handle, myAvatar->getAnimationHandles()) {
_animations->insertWidget(_animations->count() - 1, new AnimationPanel(this, handle));
}
QPushButton* newAnimation = new QPushButton("New Animation");
connect(newAnimation, SIGNAL(clicked(bool)), SLOT(addAnimation()));
layout->addWidget(newAnimation);
QDialogButtonBox* buttons = new QDialogButtonBox(QDialogButtonBox::Ok);
layout->addWidget(buttons);
connect(buttons, SIGNAL(accepted()), SLOT(deleteLater()));
_ok = buttons->button(QDialogButtonBox::Ok);
setMinimumSize(600, 600);
}
void AnimationsDialog::setVisible(bool visible) {
QDialog::setVisible(visible);
// un-default the OK button
if (visible) {
_ok->setDefault(false);
}
}
void AnimationsDialog::addAnimation() {
_animations->insertWidget(_animations->count() - 1, new AnimationPanel(this,
DependencyManager::get<AvatarManager>()->getMyAvatar()->addAnimationHandle()));
}
Setting::Handle<QString> AnimationPanel::_animationDirectory("animation_directory", QString());
AnimationPanel::AnimationPanel(AnimationsDialog* dialog, const AnimationHandlePointer& handle) :
_dialog(dialog),
_handle(handle),
_applying(false) {
setFrameStyle(QFrame::StyledPanel);
QFormLayout* layout = new QFormLayout();
layout->setFieldGrowthPolicy(QFormLayout::AllNonFixedFieldsGrow);
setLayout(layout);
layout->addRow("Role:", _role = new QComboBox());
_role->addItem("idle");
_role->addItem("sit");
_role->setEditable(true);
_role->setCurrentText(handle->getRole());
connect(_role, SIGNAL(currentTextChanged(const QString&)), SLOT(updateHandle()));
QHBoxLayout* urlBox = new QHBoxLayout();
layout->addRow("URL:", urlBox);
urlBox->addWidget(_url = new QLineEdit(handle->getURL().toString()), 1);
connect(_url, SIGNAL(editingFinished()), SLOT(updateHandle()));
QPushButton* chooseURL = new QPushButton("Choose");
urlBox->addWidget(chooseURL);
connect(chooseURL, SIGNAL(clicked(bool)), SLOT(chooseURL()));
layout->addRow("FPS:", _fps = new QDoubleSpinBox());
_fps->setSingleStep(0.01);
_fps->setMinimum(-FLT_MAX);
_fps->setMaximum(FLT_MAX);
_fps->setValue(handle->getFPS());
connect(_fps, SIGNAL(valueChanged(double)), SLOT(updateHandle()));
layout->addRow("Priority:", _priority = new QDoubleSpinBox());
_priority->setSingleStep(0.01);
_priority->setMinimum(-FLT_MAX);
_priority->setMaximum(FLT_MAX);
_priority->setValue(handle->getPriority());
connect(_priority, SIGNAL(valueChanged(double)), SLOT(updateHandle()));
QHBoxLayout* maskedJointBox = new QHBoxLayout();
layout->addRow("Masked Joints:", maskedJointBox);
maskedJointBox->addWidget(_maskedJoints = new QLineEdit(handle->getMaskedJoints().join(", ")), 1);
connect(_maskedJoints, SIGNAL(editingFinished()), SLOT(updateHandle()));
maskedJointBox->addWidget(_chooseMaskedJoints = new QPushButton("Choose"));
connect(_chooseMaskedJoints, SIGNAL(clicked(bool)), SLOT(chooseMaskedJoints()));
layout->addRow("Loop:", _loop = new QCheckBox());
_loop->setChecked(handle->getLoop());
connect(_loop, SIGNAL(toggled(bool)), SLOT(updateHandle()));
layout->addRow("Hold:", _hold = new QCheckBox());
_hold->setChecked(handle->getHold());
connect(_hold, SIGNAL(toggled(bool)), SLOT(updateHandle()));
layout->addRow("Start Automatically:", _startAutomatically = new QCheckBox());
_startAutomatically->setChecked(handle->getStartAutomatically());
connect(_startAutomatically, SIGNAL(toggled(bool)), SLOT(updateHandle()));
layout->addRow("First Frame:", _firstFrame = new QDoubleSpinBox());
_firstFrame->setSingleStep(0.01);
_firstFrame->setMaximum(INT_MAX);
_firstFrame->setValue(handle->getFirstFrame());
connect(_firstFrame, SIGNAL(valueChanged(double)), SLOT(updateHandle()));
layout->addRow("Last Frame:", _lastFrame = new QDoubleSpinBox());
_lastFrame->setSingleStep(0.01);
_lastFrame->setMaximum(INT_MAX);
_lastFrame->setValue(handle->getLastFrame());
connect(_lastFrame, SIGNAL(valueChanged(double)), SLOT(updateHandle()));
QHBoxLayout* buttons = new QHBoxLayout();
layout->addRow(buttons);
buttons->addWidget(_start = new QPushButton("Start"));
_handle->connect(_start, SIGNAL(clicked(bool)), SLOT(start()));
buttons->addWidget(_stop = new QPushButton("Stop"));
_handle->connect(_stop, SIGNAL(clicked(bool)), SLOT(stop()));
QPushButton* remove = new QPushButton("Delete");
buttons->addWidget(remove);
connect(remove, SIGNAL(clicked(bool)), SLOT(removeHandle()));
_stop->connect(_handle.get(), SIGNAL(runningChanged(bool)), SLOT(setEnabled(bool)));
_stop->setEnabled(_handle->isRunning());
}
void AnimationPanel::chooseURL() {
QString filename = QFileDialog::getOpenFileName(this, "Choose Animation",
_animationDirectory.get(), "Animation files (*.fbx)");
if (filename.isEmpty()) {
return;
}
_animationDirectory.set(QFileInfo(filename).path());
_url->setText(QUrl::fromLocalFile(filename).toString());
emit _url->editingFinished();
}
void AnimationPanel::chooseMaskedJoints() {
QMenu menu;
QStringList maskedJoints = _handle->getMaskedJoints();
foreach (const QString& jointName, DependencyManager::get<AvatarManager>()->getMyAvatar()->getJointNames()) {
QAction* action = menu.addAction(jointName);
action->setCheckable(true);
action->setChecked(maskedJoints.contains(jointName));
}
QAction* action = menu.exec(_chooseMaskedJoints->mapToGlobal(QPoint(0, 0)));
if (action) {
if (action->isChecked()) {
maskedJoints.append(action->text());
} else {
maskedJoints.removeOne(action->text());
}
_handle->setMaskedJoints(maskedJoints);
_maskedJoints->setText(maskedJoints.join(", "));
}
}
void AnimationPanel::updateHandle() {
_handle->setRole(_role->currentText());
_handle->setURL(_url->text());
_handle->setFPS(_fps->value());
_handle->setPriority(_priority->value());
_handle->setLoop(_loop->isChecked());
_handle->setHold(_hold->isChecked());
_handle->setStartAutomatically(_startAutomatically->isChecked());
_handle->setFirstFrame(_firstFrame->value());
_handle->setLastFrame(_lastFrame->value());
_handle->setMaskedJoints(_maskedJoints->text().split(QRegExp("\\s*,\\s*")));
}
void AnimationPanel::removeHandle() {
DependencyManager::get<AvatarManager>()->getMyAvatar()->removeAnimationHandle(_handle);
deleteLater();
}

View file

@ -1,87 +0,0 @@
//
// AnimationsDialog.h
// interface/src/ui
//
// Created by Andrzej Kapolka on 5/19/14.
// Copyright 2014 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#ifndef hifi_AnimationsDialog_h
#define hifi_AnimationsDialog_h
#include <QDialog>
#include <QDoubleSpinBox>
#include <QFrame>
#include <SettingHandle.h>
#include "avatar/MyAvatar.h"
class QCheckBox;
class QComboBox;
class QDoubleSpinner;
class QLineEdit;
class QPushButton;
class QVBoxLayout;
/// Allows users to edit the avatar animations.
class AnimationsDialog : public QDialog {
Q_OBJECT
public:
AnimationsDialog(QWidget* parent = nullptr);
virtual void setVisible(bool visible);
private slots:
void addAnimation();
private:
QVBoxLayout* _animations = nullptr;
QPushButton* _ok = nullptr;
};
/// A panel controlling a single animation.
class AnimationPanel : public QFrame {
Q_OBJECT
public:
AnimationPanel(AnimationsDialog* dialog, const AnimationHandlePointer& handle);
private slots:
void chooseURL();
void chooseMaskedJoints();
void updateHandle();
void removeHandle();
private:
AnimationsDialog* _dialog = nullptr;
AnimationHandlePointer _handle;
QComboBox* _role = nullptr;
QLineEdit* _url = nullptr;
QDoubleSpinBox* _fps = nullptr;
QDoubleSpinBox* _priority = nullptr;
QCheckBox* _loop = nullptr;
QCheckBox* _hold = nullptr;
QCheckBox* _startAutomatically = nullptr;
QDoubleSpinBox* _firstFrame = nullptr;
QDoubleSpinBox* _lastFrame = nullptr;
QLineEdit* _maskedJoints = nullptr;
QPushButton* _chooseMaskedJoints = nullptr;
QPushButton* _start = nullptr;
QPushButton* _stop = nullptr;
bool _applying;
static Setting::Handle<QString> _animationDirectory;
};
#endif // hifi_AnimationsDialog_h

View file

@ -19,7 +19,6 @@
#include <PathUtils.h>
#include "AddressBarDialog.h"
#include "AnimationsDialog.h"
#include "AttachmentsDialog.h"
#include "BandwidthDialog.h"
#include "CachesSizeDialog.h"
@ -110,15 +109,6 @@ void DialogsManager::editAttachments() {
}
}
void DialogsManager::editAnimations() {
if (!_animationsDialog) {
maybeCreateDialog(_animationsDialog);
_animationsDialog->show();
} else {
_animationsDialog->close();
}
}
void DialogsManager::audioStatsDetails() {
if (! _audioStatsDialog) {
_audioStatsDialog = new AudioStatsDialog(qApp->getWindow());

View file

@ -52,7 +52,6 @@ public slots:
void cachesSizeDialog();
void editPreferences();
void editAttachments();
void editAnimations();
void audioStatsDetails();
void bandwidthDetails();
void lodTools();

View file

@ -247,12 +247,7 @@ void PreferencesDialog::savePreferences() {
myAvatar->setLeanScale(ui.leanScaleSpin->value());
myAvatar->setClampedTargetScale(ui.avatarScaleSpin->value());
if (myAvatar->getAnimGraphUrl() != ui.avatarAnimationEdit->text()) { // If changed, destroy the old and start with the new
bool isEnabled = myAvatar->getEnableAnimGraph();
myAvatar->setEnableAnimGraph(false);
myAvatar->setAnimGraphUrl(ui.avatarAnimationEdit->text());
if (isEnabled) {
myAvatar->setEnableAnimGraph(true);
}
}
myAvatar->setRealWorldFieldOfView(ui.realWorldFieldOfViewSpin->value());

View file

@ -10,7 +10,7 @@
//
#include "ModelOverlay.h"
#include "EntityRig.h"
#include <Rig.h>
#include "Application.h"
@ -18,7 +18,7 @@
QString const ModelOverlay::TYPE = "model";
ModelOverlay::ModelOverlay()
: _model(std::make_shared<EntityRig>()),
: _model(std::make_shared<Rig>()),
_modelTextures(QVariantMap()),
_updateModel(false)
{
@ -28,7 +28,7 @@ ModelOverlay::ModelOverlay()
ModelOverlay::ModelOverlay(const ModelOverlay* modelOverlay) :
Volume3DOverlay(modelOverlay),
_model(std::make_shared<EntityRig>()),
_model(std::make_shared<Rig>()),
_modelTextures(QVariantMap()),
_url(modelOverlay->_url),
_updateModel(false)

View file

@ -91,57 +91,64 @@ void AnimClip::copyFromNetworkAnim() {
// build a mapping from animation joint indices to skeleton joint indices.
// by matching joints with the same name.
const FBXGeometry& geom = _networkAnim->getGeometry();
const QVector<FBXJoint>& animJoints = geom.joints;
AnimSkeleton animSkeleton(geom);
const int animJointCount = animSkeleton.getNumJoints();
const int skeletonJointCount = _skeleton->getNumJoints();
std::vector<int> jointMap;
const int animJointCount = animJoints.count();
jointMap.reserve(animJointCount);
for (int i = 0; i < animJointCount; i++) {
int skeletonJoint = _skeleton->nameToJointIndex(animJoints.at(i).name);
int skeletonJoint = _skeleton->nameToJointIndex(animSkeleton.getJointName(i));
if (skeletonJoint == -1) {
qCWarning(animation) << "animation contains joint =" << animJoints.at(i).name << " which is not in the skeleton, url =" << _url;
qCWarning(animation) << "animation contains joint =" << animSkeleton.getJointName(i) << " which is not in the skeleton, url =" << _url;
}
jointMap.push_back(skeletonJoint);
}
const int frameCount = geom.animationFrames.size();
const int skeletonJointCount = _skeleton->getNumJoints();
_anim.resize(frameCount);
const glm::vec3 offsetScale = extractScale(geom.offset);
for (int frame = 0; frame < frameCount; frame++) {
// init all joints in animation to bind pose
// this will give us a resonable result for bones in the skeleton but not in the animation.
// init all joints in animation to default pose
// this will give us a resonable result for bones in the model skeleton but not in the animation.
_anim[frame].reserve(skeletonJointCount);
for (int skeletonJoint = 0; skeletonJoint < skeletonJointCount; skeletonJoint++) {
_anim[frame].push_back(_skeleton->getRelativeBindPose(skeletonJoint));
_anim[frame].push_back(_skeleton->getRelativeDefaultPose(skeletonJoint));
}
for (int animJoint = 0; animJoint < animJointCount; animJoint++) {
int skeletonJoint = jointMap[animJoint];
// skip joints that are in the animation but not in the skeleton.
if (skeletonJoint >= 0 && skeletonJoint < skeletonJointCount) {
const glm::vec3& fbxZeroTrans = geom.animationFrames[0].translations[animJoint] * offsetScale;
const AnimPose& relBindPose = _skeleton->getRelativeBindPose(skeletonJoint);
const glm::vec3& fbxZeroTrans = geom.animationFrames[0].translations[animJoint];
#ifdef USE_PRE_ROT_FROM_ANIM
// TODO: This is the correct way to apply the pre rotations from maya, however
// the current animation set has incorrect preRotations for the left wrist and thumb
// so it looks wrong if we enable this code.
glm::quat preRotation = animSkeleton.getPreRotation(animJoint);
#else
// TODO: This is the legacy approach, this does not work when animations and models do not
// have the same set of pre rotations. For example when mixing maya models with blender animations.
glm::quat preRotation = _skeleton->getRelativeBindPose(skeletonJoint).rot;
#endif
const AnimPose& relDefaultPose = _skeleton->getRelativeDefaultPose(skeletonJoint);
// used to adjust translation offsets, so large translation animatons on the reference skeleton
// will be adjusted when played on a skeleton with short limbs.
float limbLengthScale = fabsf(glm::length(fbxZeroTrans)) <= 0.0001f ? 1.0f : (glm::length(relBindPose.trans) / glm::length(fbxZeroTrans));
float limbLengthScale = fabsf(glm::length(fbxZeroTrans)) <= 0.0001f ? 1.0f : (glm::length(relDefaultPose.trans) / glm::length(fbxZeroTrans));
AnimPose& pose = _anim[frame][skeletonJoint];
const FBXAnimationFrame& fbxAnimFrame = geom.animationFrames[frame];
// rotation in fbxAnimationFrame is a delta from a reference skeleton bind pose.
pose.rot = relBindPose.rot * fbxAnimFrame.rotations[animJoint];
// rotation in fbxAnimationFrame is a delta from its preRotation.
pose.rot = preRotation * fbxAnimFrame.rotations[animJoint];
// translation in fbxAnimationFrame is not a delta.
// convert it into a delta by subtracting from the first frame.
const glm::vec3& fbxTrans = fbxAnimFrame.translations[animJoint] * offsetScale;
pose.trans = relBindPose.trans + limbLengthScale * (fbxTrans - fbxZeroTrans);
const glm::vec3& fbxTrans = fbxAnimFrame.translations[animJoint];
pose.trans = relDefaultPose.trans + limbLengthScale * (fbxTrans - fbxZeroTrans);
}
}
}

View file

@ -37,13 +37,18 @@ public:
void setFrameVar(const QString& frameVar) { _frameVar = frameVar; }
float getStartFrame() const { return _startFrame; }
void setStartFrame(float startFrame) { _startFrame = startFrame; }
float getEndFrame() const { return _endFrame; }
void setEndFrame(float endFrame) { _endFrame = endFrame; }
void setTimeScale(float timeScale) { _timeScale = timeScale; }
float getTimeScale() const { return _timeScale; }
protected:
bool getLoopFlag() const { return _loopFlag; }
void setLoopFlag(bool loopFlag) { _loopFlag = loopFlag; }
void loadURL(const QString& url);
protected:
virtual void setCurrentFrameInternal(float frame) override;

View file

@ -98,8 +98,8 @@ void AnimInverseKinematics::computeTargets(const AnimVariantMap& animVars, std::
target.setType(animVars.lookup(targetVar.typeVar, (int)IKTarget::Type::RotationAndPosition));
if (target.getType() != IKTarget::Type::Unknown) {
AnimPose defaultPose = _skeleton->getAbsolutePose(targetVar.jointIndex, underPoses);
glm::quat rotation = animVars.lookup(targetVar.rotationVar, defaultPose.rot);
glm::vec3 translation = animVars.lookup(targetVar.positionVar, defaultPose.trans);
glm::quat rotation = animVars.lookupRigToGeometry(targetVar.rotationVar, defaultPose.rot);
glm::vec3 translation = animVars.lookupRigToGeometry(targetVar.positionVar, defaultPose.trans);
if (target.getType() == IKTarget::Type::HipsRelativeRotationAndPosition) {
translation += _hipsOffset;
}

View file

@ -54,9 +54,9 @@ protected:
AnimInverseKinematics& operator=(const AnimInverseKinematics&) = delete;
struct IKTargetVar {
IKTargetVar(const QString& jointNameIn,
const QString& positionVarIn,
const QString& rotationVarIn,
IKTargetVar(const QString& jointNameIn,
const QString& positionVarIn,
const QString& rotationVarIn,
const QString& typeVarIn) :
positionVar(positionVarIn),
rotationVar(rotationVarIn),

View file

@ -46,39 +46,15 @@ const AnimPoseVec& AnimManipulator::overlay(const AnimVariantMap& animVars, floa
if (jointVar.jointIndex >= 0) {
AnimPose defaultAbsPose;
// use the underPose as our default value if we can.
AnimPose defaultRelPose;
AnimPose parentAbsPose = AnimPose::identity;
if (jointVar.jointIndex <= (int)underPoses.size()) {
// jointVar is an absolute rotation, if it is not set we will use the underPose as our default value
defaultRelPose = underPoses[jointVar.jointIndex];
defaultAbsPose = _skeleton->getAbsolutePose(jointVar.jointIndex, underPoses);
defaultAbsPose.rot = animVars.lookup(jointVar.var, defaultAbsPose.rot);
// because jointVar is absolute, we must use an absolute parent frame to convert into a relative pose.
int parentIndex = _skeleton->getParentIndex(jointVar.jointIndex);
if (parentIndex >= 0) {
parentAbsPose = _skeleton->getAbsolutePose(parentIndex, underPoses);
}
} else {
// jointVar is an absolute rotation, if it is not set we will use the bindPose as our default value
defaultRelPose = AnimPose::identity;
defaultAbsPose = _skeleton->getAbsoluteBindPose(jointVar.jointIndex);
defaultAbsPose.rot = animVars.lookup(jointVar.var, defaultAbsPose.rot);
// because jointVar is absolute, we must use an absolute parent frame to convert into a relative pose
// here we use the bind pose
int parentIndex = _skeleton->getParentIndex(jointVar.jointIndex);
if (parentIndex >= 0) {
parentAbsPose = _skeleton->getAbsoluteBindPose(parentIndex);
}
}
// convert from absolute to relative
AnimPose relPose = parentAbsPose.inverse() * defaultAbsPose;
AnimPose relPose = computeRelativePoseFromJointVar(animVars, jointVar, defaultRelPose, underPoses);
// blend with underPose
::blend(1, &defaultRelPose, &relPose, _alpha, &_poses[jointVar.jointIndex]);
@ -114,3 +90,44 @@ const AnimPoseVec& AnimManipulator::getPosesInternal() const {
void AnimManipulator::addJointVar(const JointVar& jointVar) {
_jointVars.push_back(jointVar);
}
void AnimManipulator::removeAllJointVars() {
_jointVars.clear();
}
AnimPose AnimManipulator::computeRelativePoseFromJointVar(const AnimVariantMap& animVars, const JointVar& jointVar,
const AnimPose& defaultRelPose, const AnimPoseVec& underPoses) {
AnimPose defaultAbsPose = _skeleton->getAbsolutePose(jointVar.jointIndex, underPoses);
if (jointVar.type == JointVar::Type::AbsoluteRotation || jointVar.type == JointVar::Type::AbsolutePosition) {
if (jointVar.type == JointVar::Type::AbsoluteRotation) {
defaultAbsPose.rot = animVars.lookupRigToGeometry(jointVar.var, defaultAbsPose.rot);
} else if (jointVar.type == JointVar::Type::AbsolutePosition) {
defaultAbsPose.trans = animVars.lookupRigToGeometry(jointVar.var, defaultAbsPose.trans);
}
// because jointVar is absolute, we must use an absolute parent frame to convert into a relative pose.
AnimPose parentAbsPose = AnimPose::identity;
int parentIndex = _skeleton->getParentIndex(jointVar.jointIndex);
if (parentIndex >= 0) {
parentAbsPose = _skeleton->getAbsolutePose(parentIndex, underPoses);
}
// convert from absolute to relative
return parentAbsPose.inverse() * defaultAbsPose;
} else {
// override the default rel pose
AnimPose relPose = defaultRelPose;
if (jointVar.type == JointVar::Type::RelativeRotation) {
relPose.rot = animVars.lookupRigToGeometry(jointVar.var, defaultRelPose.rot);
} else if (jointVar.type == JointVar::Type::RelativePosition) {
relPose.trans = animVars.lookupRigToGeometry(jointVar.var, defaultRelPose.trans);
}
return relPose;
}
}

View file

@ -30,19 +30,33 @@ public:
virtual void setSkeletonInternal(AnimSkeleton::ConstPointer skeleton) override;
struct JointVar {
JointVar(const QString& varIn, const QString& jointNameIn) : var(varIn), jointName(jointNameIn), jointIndex(-1), hasPerformedJointLookup(false) {}
enum class Type {
AbsoluteRotation = 0,
AbsolutePosition,
RelativeRotation,
RelativePosition,
NumTypes
};
JointVar(const QString& varIn, const QString& jointNameIn, Type typeIn) : var(varIn), jointName(jointNameIn), type(typeIn), jointIndex(-1), hasPerformedJointLookup(false) {}
QString var = "";
QString jointName = "";
Type type = Type::AbsoluteRotation;
int jointIndex = -1;
bool hasPerformedJointLookup = false;
bool isRelative = false;
};
void addJointVar(const JointVar& jointVar);
void removeAllJointVars();
protected:
// for AnimDebugDraw rendering
virtual const AnimPoseVec& getPosesInternal() const override;
AnimPose computeRelativePoseFromJointVar(const AnimVariantMap& animVars, const JointVar& jointVar,
const AnimPose& defaultRelPose, const AnimPoseVec& underPoses);
AnimPoseVec _poses;
float _alpha;
QString _alphaVar;

View file

@ -8,12 +8,35 @@
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#include <QtGlobal>
#include "AnimNode.h"
void AnimNode::removeChild(AnimNode::Pointer child) {
AnimNode::Pointer AnimNode::getParent() {
return _parent.lock();
}
void AnimNode::addChild(Pointer child) {
_children.push_back(child);
child->_parent = shared_from_this();
}
void AnimNode::removeChild(Pointer child) {
auto iter = std::find(_children.begin(), _children.end(), child);
if (iter != _children.end()) {
_children.erase(iter);
child->_parent.reset();
}
}
void AnimNode::replaceChild(Pointer oldChild, Pointer newChild) {
auto iter = std::find(_children.begin(), _children.end(), oldChild);
if (iter != _children.end()) {
oldChild->_parent.reset();
newChild->_parent = shared_from_this();
if (_skeleton) {
newChild->setSkeleton(_skeleton);
}
*iter = newChild;
}
}
@ -22,7 +45,7 @@ AnimNode::Pointer AnimNode::getChild(int i) const {
return _children[i];
}
void AnimNode::setSkeleton(const AnimSkeleton::Pointer skeleton) {
void AnimNode::setSkeleton(AnimSkeleton::ConstPointer skeleton) {
setSkeletonInternal(skeleton);
for (auto&& child : _children) {
child->setSkeleton(skeleton);

View file

@ -33,7 +33,7 @@ class QJsonObject;
// * evaluate method, perform actual joint manipulations here and return result by reference.
// Also, append any triggers that are detected during evaluation.
class AnimNode {
class AnimNode : public std::enable_shared_from_this<AnimNode> {
public:
enum class Type {
Clip = 0,
@ -60,14 +60,15 @@ public:
Type getType() const { return _type; }
// hierarchy accessors
void addChild(Pointer child) { _children.push_back(child); }
Pointer getParent();
void addChild(Pointer child);
void removeChild(Pointer child);
void replaceChild(Pointer oldChild, Pointer newChild);
Pointer getChild(int i) const;
int getChildCount() const { return (int)_children.size(); }
// pair this AnimNode graph with a skeleton.
void setSkeleton(const AnimSkeleton::Pointer skeleton);
void setSkeleton(AnimSkeleton::ConstPointer skeleton);
AnimSkeleton::ConstPointer getSkeleton() const { return _skeleton; }
@ -78,6 +79,30 @@ public:
void setCurrentFrame(float frame);
template <typename F>
bool traverse(F func) {
if (func(shared_from_this())) {
for (auto&& child : _children) {
if (!child->traverse(func)) {
return false;
}
}
}
return true;
}
Pointer findByName(const QString& id) {
Pointer result;
traverse([&](Pointer node) {
if (id == node->getID()) {
result = node;
return false;
}
return true;
});
return result;
}
protected:
virtual void setCurrentFrameInternal(float frame) {}
@ -90,6 +115,7 @@ protected:
QString _id;
std::vector<AnimNode::Pointer> _children;
AnimSkeleton::ConstPointer _skeleton;
std::weak_ptr<AnimNode> _parent;
// no copies
AnimNode(const AnimNode&) = delete;

View file

@ -55,6 +55,41 @@ static const char* animNodeTypeToString(AnimNode::Type type) {
return nullptr;
}
static AnimNode::Type stringToAnimNodeType(const QString& str) {
// O(n), move to map when number of types becomes large.
const int NUM_TYPES = static_cast<int>(AnimNode::Type::NumTypes);
for (int i = 0; i < NUM_TYPES; i++) {
AnimNode::Type type = static_cast<AnimNode::Type>(i);
if (str == animNodeTypeToString(type)) {
return type;
}
}
return AnimNode::Type::NumTypes;
}
static const char* animManipulatorJointVarTypeToString(AnimManipulator::JointVar::Type type) {
switch (type) {
case AnimManipulator::JointVar::Type::AbsoluteRotation: return "absoluteRotation";
case AnimManipulator::JointVar::Type::AbsolutePosition: return "absolutePosition";
case AnimManipulator::JointVar::Type::RelativeRotation: return "relativeRotation";
case AnimManipulator::JointVar::Type::RelativePosition: return "relativePosition";
case AnimManipulator::JointVar::Type::NumTypes: return nullptr;
};
return nullptr;
}
static AnimManipulator::JointVar::Type stringToAnimManipulatorJointVarType(const QString& str) {
// O(n), move to map when number of types becomes large.
const int NUM_TYPES = static_cast<int>(AnimManipulator::JointVar::Type::NumTypes);
for (int i = 0; i < NUM_TYPES; i++) {
AnimManipulator::JointVar::Type type = static_cast<AnimManipulator::JointVar::Type>(i);
if (str == animManipulatorJointVarTypeToString(type)) {
return type;
}
}
return AnimManipulator::JointVar::Type::NumTypes;
}
static NodeLoaderFunc animNodeTypeToLoaderFunc(AnimNode::Type type) {
switch (type) {
case AnimNode::Type::Clip: return loadClipNode;
@ -120,17 +155,6 @@ static NodeProcessFunc animNodeTypeToProcessFunc(AnimNode::Type type) {
} \
float NAME = (float)NAME##_VAL.toDouble()
static AnimNode::Type stringToEnum(const QString& str) {
// O(n), move to map when number of types becomes large.
const int NUM_TYPES = static_cast<int>(AnimNode::Type::NumTypes);
for (int i = 0; i < NUM_TYPES; i++) {
AnimNode::Type type = static_cast<AnimNode::Type>(i);
if (str == animNodeTypeToString(type)) {
return type;
}
}
return AnimNode::Type::NumTypes;
}
static AnimNode::Pointer loadNode(const QJsonObject& jsonObj, const QUrl& jsonUrl) {
auto idVal = jsonObj.value("id");
@ -146,7 +170,7 @@ static AnimNode::Pointer loadNode(const QJsonObject& jsonObj, const QUrl& jsonUr
return nullptr;
}
QString typeStr = typeVal.toString();
AnimNode::Type type = stringToEnum(typeStr);
AnimNode::Type type = stringToAnimNodeType(typeStr);
if (type == AnimNode::Type::NumTypes) {
qCCritical(animation) << "AnimNodeLoader, unknown node type" << typeStr << ", id =" << id << ", url =" << jsonUrl.toDisplayString();
return nullptr;
@ -355,10 +379,17 @@ static AnimNode::Pointer loadManipulatorNode(const QJsonObject& jsonObj, const Q
}
auto jointObj = jointValue.toObject();
READ_STRING(var, jointObj, id, jsonUrl, nullptr);
READ_STRING(type, jointObj, id, jsonUrl, nullptr);
READ_STRING(jointName, jointObj, id, jsonUrl, nullptr);
READ_STRING(var, jointObj, id, jsonUrl, nullptr);
AnimManipulator::JointVar jointVar(var, jointName);
AnimManipulator::JointVar::Type jointVarType = stringToAnimManipulatorJointVarType(type);
if (jointVarType == AnimManipulator::JointVar::Type::NumTypes) {
qCCritical(animation) << "AnimNodeLoader, bad type in \"joints\", id =" << id << ", url =" << jsonUrl.toDisplayString();
return nullptr;
}
AnimManipulator::JointVar jointVar(var, jointName, jointVarType);
node->addJointVar(jointVar);
};
@ -393,9 +424,9 @@ AnimNode::Pointer loadInverseKinematicsNode(const QJsonObject& jsonObj, const QS
return node;
}
void buildChildMap(std::map<QString, AnimNode::Pointer>& map, AnimNode::Pointer node) {
for ( auto child : node->_children ) {
map.insert(std::pair<QString, AnimNode::Pointer>(child->_id, child));
void buildChildMap(std::map<QString, int>& map, AnimNode::Pointer node) {
for (int i = 0; i < (int)node->getChildCount(); ++i) {
map.insert(std::pair<QString, int>(node->getChild(i)->getID(), i));
}
}
@ -412,7 +443,7 @@ bool processStateMachineNode(AnimNode::Pointer node, const QJsonObject& jsonObj,
}
// build a map for all children by name.
std::map<QString, AnimNode::Pointer> childMap;
std::map<QString, int> childMap;
buildChildMap(childMap, node);
// first pass parse all the states and build up the state and transition map.

View file

@ -9,7 +9,8 @@
//
#include "AnimPose.h"
#include "GLMHelpers.h"
#include <GLMHelpers.h>
#include <algorithm>
const AnimPose AnimPose::identity = AnimPose(glm::vec3(1.0f),
glm::quat(),
@ -17,7 +18,7 @@ const AnimPose AnimPose::identity = AnimPose(glm::vec3(1.0f),
AnimPose::AnimPose(const glm::mat4& mat) {
scale = extractScale(mat);
rot = glm::normalize(glm::quat_cast(mat));
rot = glmExtractRotation(mat);
trans = extractTranslation(mat);
}

View file

@ -23,13 +23,11 @@ AnimSkeleton::AnimSkeleton(const FBXGeometry& fbxGeometry) {
for (auto& joint : fbxGeometry.joints) {
joints.push_back(joint);
}
AnimPose geometryOffset(fbxGeometry.offset);
buildSkeletonFromJoints(joints, geometryOffset);
buildSkeletonFromJoints(joints);
}
AnimSkeleton::AnimSkeleton(const std::vector<FBXJoint>& joints, const AnimPose& geometryOffset) {
buildSkeletonFromJoints(joints, geometryOffset);
AnimSkeleton::AnimSkeleton(const std::vector<FBXJoint>& joints) {
buildSkeletonFromJoints(joints);
}
int AnimSkeleton::nameToJointIndex(const QString& jointName) const {
@ -53,6 +51,18 @@ const AnimPose& AnimSkeleton::getRelativeBindPose(int jointIndex) const {
return _relativeBindPoses[jointIndex];
}
const AnimPose& AnimSkeleton::getRelativeDefaultPose(int jointIndex) const {
return _relativeDefaultPoses[jointIndex];
}
const AnimPose& AnimSkeleton::getAbsoluteDefaultPose(int jointIndex) const {
return _absoluteDefaultPoses[jointIndex];
}
const glm::quat AnimSkeleton::getPreRotation(int jointIndex) const {
return _joints[jointIndex].preRotation;
}
int AnimSkeleton::getParentIndex(int jointIndex) const {
return _joints[jointIndex].parentIndex;
}
@ -69,21 +79,48 @@ AnimPose AnimSkeleton::getAbsolutePose(int jointIndex, const AnimPoseVec& poses)
}
}
void AnimSkeleton::buildSkeletonFromJoints(const std::vector<FBXJoint>& joints, const AnimPose& geometryOffset) {
void AnimSkeleton::convertRelativePosesToAbsolute(AnimPoseVec& poses) const {
// poses start off relative and leave in absolute frame
for (int i = 0; i < (int)poses.size() && i < (int)_joints.size(); ++i) {
int parentIndex = _joints[i].parentIndex;
if (parentIndex != -1) {
poses[i] = poses[parentIndex] * poses[i];
}
}
}
void AnimSkeleton::buildSkeletonFromJoints(const std::vector<FBXJoint>& joints) {
_joints = joints;
// build a cache of bind poses
_absoluteBindPoses.reserve(joints.size());
_relativeBindPoses.reserve(joints.size());
// build a chache of default poses
_absoluteDefaultPoses.reserve(joints.size());
_relativeDefaultPoses.reserve(joints.size());
// iterate over FBXJoints and extract the bind pose information.
for (size_t i = 0; i < joints.size(); i++) {
// build relative and absolute default poses
glm::mat4 rotTransform = glm::mat4_cast(_joints[i].preRotation * _joints[i].rotation * _joints[i].postRotation);
glm::mat4 relDefaultMat = glm::translate(_joints[i].translation) * _joints[i].preTransform * rotTransform * _joints[i].postTransform;
AnimPose relDefaultPose(relDefaultMat);
_relativeDefaultPoses.push_back(relDefaultPose);
int parentIndex = getParentIndex(i);
if (parentIndex >= 0) {
_absoluteDefaultPoses.push_back(_absoluteDefaultPoses[parentIndex] * relDefaultPose);
} else {
_absoluteDefaultPoses.push_back(relDefaultPose);
}
// build relative and absolute bind poses
if (_joints[i].bindTransformFoundInCluster) {
// Use the FBXJoint::bindTransform, which is absolute model coordinates
// i.e. not relative to it's parent.
AnimPose absoluteBindPose(_joints[i].bindTransform);
_absoluteBindPoses.push_back(absoluteBindPose);
int parentIndex = getParentIndex(i);
if (parentIndex >= 0) {
AnimPose inverseParentAbsoluteBindPose = _absoluteBindPoses[parentIndex].inverse();
_relativeBindPoses.push_back(inverseParentAbsoluteBindPose * absoluteBindPose);
@ -91,37 +128,15 @@ void AnimSkeleton::buildSkeletonFromJoints(const std::vector<FBXJoint>& joints,
_relativeBindPoses.push_back(absoluteBindPose);
}
} else {
// use FBXJoint's local transform, instead
glm::mat4 rotTransform = glm::mat4_cast(_joints[i].preRotation * _joints[i].rotation * _joints[i].postRotation);
glm::mat4 relBindMat = glm::translate(_joints[i].translation) * _joints[i].preTransform * rotTransform * _joints[i].postTransform;
AnimPose relBindPose(relBindMat);
_relativeBindPoses.push_back(relBindPose);
int parentIndex = getParentIndex(i);
// use default transform instead
_relativeBindPoses.push_back(relDefaultPose);
if (parentIndex >= 0) {
_absoluteBindPoses.push_back(_absoluteBindPoses[parentIndex] * relBindPose);
_absoluteBindPoses.push_back(_absoluteBindPoses[parentIndex] * relDefaultPose);
} else {
_absoluteBindPoses.push_back(relBindPose);
_absoluteBindPoses.push_back(relDefaultPose);
}
}
}
// now we want to normalize scale from geometryOffset to all poses.
// This will ensure our bone translations will be in meters, even if the model was authored with some other unit of mesure.
for (auto& absPose : _absoluteBindPoses) {
absPose.trans = (geometryOffset * absPose).trans;
absPose.scale = vec3(1, 1, 1);
}
// re-compute relative poses based on the modified absolute poses.
for (size_t i = 0; i < _relativeBindPoses.size(); i++) {
int parentIndex = getParentIndex(i);
if (parentIndex >= 0) {
_relativeBindPoses[i] = _absoluteBindPoses[parentIndex].inverse() * _absoluteBindPoses[i];
} else {
_relativeBindPoses[i] = _absoluteBindPoses[i];
}
}
}
#ifndef NDEBUG
@ -133,6 +148,25 @@ void AnimSkeleton::dump() const {
qCDebug(animation) << " name =" << getJointName(i);
qCDebug(animation) << " absBindPose =" << getAbsoluteBindPose(i);
qCDebug(animation) << " relBindPose =" << getRelativeBindPose(i);
qCDebug(animation) << " absDefaultPose =" << getAbsoluteDefaultPose(i);
qCDebug(animation) << " relDefaultPose =" << getRelativeDefaultPose(i);
#ifdef DUMP_FBX_JOINTS
qCDebug(animation) << " isFree =" << _joints[i].isFree;
qCDebug(animation) << " freeLineage =" << _joints[i].freeLineage;
qCDebug(animation) << " parentIndex =" << _joints[i].parentIndex;
qCDebug(animation) << " translation =" << _joints[i].translation;
qCDebug(animation) << " preTransform =" << _joints[i].preTransform;
qCDebug(animation) << " preRotation =" << _joints[i].preRotation;
qCDebug(animation) << " rotation =" << _joints[i].rotation;
qCDebug(animation) << " postRotation =" << _joints[i].postRotation;
qCDebug(animation) << " postTransform =" << _joints[i].postTransform;
qCDebug(animation) << " transform =" << _joints[i].transform;
qCDebug(animation) << " rotationMin =" << _joints[i].rotationMin << ", rotationMax =" << _joints[i].rotationMax;
qCDebug(animation) << " inverseDefaultRotation" << _joints[i].inverseDefaultRotation;
qCDebug(animation) << " inverseBindRotation" << _joints[i].inverseBindRotation;
qCDebug(animation) << " bindTransform" << _joints[i].bindTransform;
qCDebug(animation) << " isSkeletonJoint" << _joints[i].isSkeletonJoint;
#endif
if (getParentIndex(i) >= 0) {
qCDebug(animation) << " parent =" << getJointName(getParentIndex(i));
}
@ -149,6 +183,8 @@ void AnimSkeleton::dump(const AnimPoseVec& poses) const {
qCDebug(animation) << " name =" << getJointName(i);
qCDebug(animation) << " absBindPose =" << getAbsoluteBindPose(i);
qCDebug(animation) << " relBindPose =" << getRelativeBindPose(i);
qCDebug(animation) << " absDefaultPose =" << getAbsoluteDefaultPose(i);
qCDebug(animation) << " relDefaultPose =" << getRelativeDefaultPose(i);
qCDebug(animation) << " pose =" << poses[i];
if (getParentIndex(i) >= 0) {
qCDebug(animation) << " parent =" << getJointName(getParentIndex(i));

View file

@ -24,7 +24,7 @@ public:
using ConstPointer = std::shared_ptr<const AnimSkeleton>;
AnimSkeleton(const FBXGeometry& fbxGeometry);
AnimSkeleton(const std::vector<FBXJoint>& joints, const AnimPose& geometryOffset);
AnimSkeleton(const std::vector<FBXJoint>& joints);
int nameToJointIndex(const QString& jointName) const;
const QString& getJointName(int jointIndex) const;
int getNumJoints() const;
@ -36,21 +36,34 @@ public:
const AnimPose& getRelativeBindPose(int jointIndex) const;
const AnimPoseVec& getRelativeBindPoses() const { return _relativeBindPoses; }
// the default poses are the orientations of the joints on frame 0.
const AnimPose& getRelativeDefaultPose(int jointIndex) const;
const AnimPoseVec& getRelativeDefaultPoses() const { return _relativeDefaultPoses; }
const AnimPose& getAbsoluteDefaultPose(int jointIndex) const;
const AnimPoseVec& getAbsoluteDefaultPoses() const { return _absoluteDefaultPoses; }
// get pre-rotation aka Maya's joint orientation.
const glm::quat getPreRotation(int jointIndex) const;
int getParentIndex(int jointIndex) const;
AnimPose getAbsolutePose(int jointIndex, const AnimPoseVec& poses) const;
void convertRelativePosesToAbsolute(AnimPoseVec& poses) const;
#ifndef NDEBUG
void dump() const;
void dump(const AnimPoseVec& poses) const;
#endif
protected:
void buildSkeletonFromJoints(const std::vector<FBXJoint>& joints, const AnimPose& geometryOffset);
void buildSkeletonFromJoints(const std::vector<FBXJoint>& joints);
std::vector<FBXJoint> _joints;
AnimPoseVec _absoluteBindPoses;
AnimPoseVec _relativeBindPoses;
AnimPoseVec _relativeDefaultPoses;
AnimPoseVec _absoluteDefaultPoses;
// no copies
AnimSkeleton(const AnimSkeleton&) = delete;

View file

@ -46,7 +46,7 @@ const AnimPoseVec& AnimStateMachine::evaluate(const AnimVariantMap& animVars, fl
}
assert(_currentState);
auto currentStateNode = _currentState->getNode();
auto currentStateNode = _children[_currentState->getChildIndex()];
assert(currentStateNode);
if (_duringInterp) {
@ -79,8 +79,8 @@ void AnimStateMachine::switchState(const AnimVariantMap& animVars, State::Pointe
const float FRAMES_PER_SECOND = 30.0f;
auto prevStateNode = _currentState->getNode();
auto nextStateNode = desiredState->getNode();
auto prevStateNode = _children[_currentState->getChildIndex()];
auto nextStateNode = _children[desiredState->getChildIndex()];
_duringInterp = true;
_alpha = 0.0f;

View file

@ -55,16 +55,16 @@ protected:
State::Pointer _state;
};
State(const QString& id, AnimNode::Pointer node, float interpTarget, float interpDuration) :
State(const QString& id, int childIndex, float interpTarget, float interpDuration) :
_id(id),
_node(node),
_childIndex(childIndex),
_interpTarget(interpTarget),
_interpDuration(interpDuration) {}
void setInterpTargetVar(const QString& interpTargetVar) { _interpTargetVar = interpTargetVar; }
void setInterpDurationVar(const QString& interpDurationVar) { _interpDurationVar = interpDurationVar; }
AnimNode::Pointer getNode() const { return _node; }
int getChildIndex() const { return _childIndex; }
const QString& getID() const { return _id; }
protected:
@ -75,7 +75,7 @@ protected:
void addTransition(const Transition& transition) { _transitions.push_back(transition); }
QString _id;
AnimNode::Pointer _node;
int _childIndex;
float _interpTarget; // frames
float _interpDuration; // frames

View file

@ -18,8 +18,17 @@ void blend(size_t numPoses, const AnimPose* a, const AnimPose* b, float alpha, A
for (size_t i = 0; i < numPoses; i++) {
const AnimPose& aPose = a[i];
const AnimPose& bPose = b[i];
// adjust signs if necessary
const glm::quat& q1 = aPose.rot;
glm::quat q2 = bPose.rot;
float dot = glm::dot(q1, q2);
if (dot < 0.0f) {
q2 = -q2;
}
result[i].scale = lerp(aPose.scale, bPose.scale, alpha);
result[i].rot = glm::normalize(glm::lerp(aPose.rot, bPose.rot, alpha));
result[i].rot = glm::normalize(glm::lerp(aPose.rot, q2, alpha));
result[i].trans = lerp(aPose.trans, bPose.trans, alpha);
}
}

View file

@ -43,7 +43,7 @@ QScriptValue AnimVariantMap::animVariantMapToScriptValue(QScriptEngine* engine,
target.setProperty(name, quatToScriptValue(engine, value.getQuat()));
break;
default:
// Note that we don't do mat4 in Javascript currently, and there's not yet a reason to start now.
// Unknown type
assert(QString("AnimVariant::Type") == QString("valid"));
}
};

View file

@ -18,8 +18,9 @@
#include <map>
#include <set>
#include <QScriptValue>
#include <StreamUtils.h>
#include <GLMHelpers.h>
#include "AnimationLogging.h"
#include "StreamUtils.h"
class AnimVariant {
public:
@ -29,7 +30,6 @@ public:
Float,
Vec3,
Quat,
Mat4,
String,
NumTypes
};
@ -40,7 +40,6 @@ public:
AnimVariant(float value) : _type(Type::Float) { _val.floats[0] = value; }
AnimVariant(const glm::vec3& value) : _type(Type::Vec3) { *reinterpret_cast<glm::vec3*>(&_val) = value; }
AnimVariant(const glm::quat& value) : _type(Type::Quat) { *reinterpret_cast<glm::quat*>(&_val) = value; }
AnimVariant(const glm::mat4& value) : _type(Type::Mat4) { *reinterpret_cast<glm::mat4*>(&_val) = value; }
AnimVariant(const QString& value) : _type(Type::String) { _stringVal = value; }
bool isBool() const { return _type == Type::Bool; }
@ -48,7 +47,6 @@ public:
bool isFloat() const { return _type == Type::Float; }
bool isVec3() const { return _type == Type::Vec3; }
bool isQuat() const { return _type == Type::Quat; }
bool isMat4() const { return _type == Type::Mat4; }
bool isString() const { return _type == Type::String; }
Type getType() const { return _type; }
@ -57,7 +55,6 @@ public:
void setFloat(float value) { assert(_type == Type::Float); _val.floats[0] = value; }
void setVec3(const glm::vec3& value) { assert(_type == Type::Vec3); *reinterpret_cast<glm::vec3*>(&_val) = value; }
void setQuat(const glm::quat& value) { assert(_type == Type::Quat); *reinterpret_cast<glm::quat*>(&_val) = value; }
void setMat4(const glm::mat4& value) { assert(_type == Type::Mat4); *reinterpret_cast<glm::mat4*>(&_val) = value; }
void setString(const QString& value) { assert(_type == Type::String); _stringVal = value; }
bool getBool() const { assert(_type == Type::Bool); return _val.boolVal; }
@ -66,7 +63,6 @@ public:
const glm::vec3& getVec3() const { assert(_type == Type::Vec3); return *reinterpret_cast<const glm::vec3*>(&_val); }
const glm::quat& getQuat() const { assert(_type == Type::Quat); return *reinterpret_cast<const glm::quat*>(&_val); }
const glm::mat4& getMat4() const { assert(_type == Type::Mat4); return *reinterpret_cast<const glm::mat4*>(&_val); }
const QString& getString() const { assert(_type == Type::String); return _stringVal; }
protected:
@ -112,7 +108,7 @@ public:
}
}
const glm::vec3& lookup(const QString& key, const glm::vec3& defaultValue) const {
const glm::vec3& lookupRaw(const QString& key, const glm::vec3& defaultValue) const {
if (key.isEmpty()) {
return defaultValue;
} else {
@ -121,7 +117,16 @@ public:
}
}
const glm::quat& lookup(const QString& key, const glm::quat& defaultValue) const {
glm::vec3 lookupRigToGeometry(const QString& key, const glm::vec3& defaultValue) const {
if (key.isEmpty()) {
return defaultValue;
} else {
auto iter = _map.find(key);
return iter != _map.end() ? transformPoint(_rigToGeometryMat, iter->second.getVec3()) : defaultValue;
}
}
const glm::quat& lookupRaw(const QString& key, const glm::quat& defaultValue) const {
if (key.isEmpty()) {
return defaultValue;
} else {
@ -130,12 +135,12 @@ public:
}
}
const glm::mat4& lookup(const QString& key, const glm::mat4& defaultValue) const {
glm::quat lookupRigToGeometry(const QString& key, const glm::quat& defaultValue) const {
if (key.isEmpty()) {
return defaultValue;
} else {
auto iter = _map.find(key);
return iter != _map.end() ? iter->second.getMat4() : defaultValue;
return iter != _map.end() ? _rigToGeometryRot * iter->second.getQuat() : defaultValue;
}
}
@ -153,13 +158,17 @@ public:
void set(const QString& key, float value) { _map[key] = AnimVariant(value); }
void set(const QString& key, const glm::vec3& value) { _map[key] = AnimVariant(value); }
void set(const QString& key, const glm::quat& value) { _map[key] = AnimVariant(value); }
void set(const QString& key, const glm::mat4& value) { _map[key] = AnimVariant(value); }
void set(const QString& key, const QString& value) { _map[key] = AnimVariant(value); }
void unset(const QString& key) { _map.erase(key); }
void setTrigger(const QString& key) { _triggers.insert(key); }
void clearTriggers() { _triggers.clear(); }
void setRigToGeometryTransform(const glm::mat4& rigToGeometry) {
_rigToGeometryMat = rigToGeometry;
_rigToGeometryRot = glmExtractRotation(rigToGeometry);
}
void clearMap() { _map.clear(); }
bool hasKey(const QString& key) const { return _map.find(key) != _map.end(); }
@ -189,9 +198,6 @@ public:
case AnimVariant::Type::Quat:
qCDebug(animation) << " " << pair.first << "=" << pair.second.getQuat();
break;
case AnimVariant::Type::Mat4:
qCDebug(animation) << " " << pair.first << "=" << pair.second.getMat4();
break;
case AnimVariant::Type::String:
qCDebug(animation) << " " << pair.first << "=" << pair.second.getString();
break;
@ -205,6 +211,8 @@ public:
protected:
std::map<QString, AnimVariant> _map;
std::set<QString> _triggers;
glm::mat4 _rigToGeometryMat;
glm::quat _rigToGeometryRot;
};
typedef std::function<void(QScriptValue)> AnimVariantResultHandler;

View file

@ -1,218 +0,0 @@
//
// AnimationHandle.cpp
// libraries/animation/src/
//
// Created by Andrzej Kapolka on 10/18/13.
// Copyright 2013 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#include "AnimationHandle.h"
#include "AnimationLogging.h"
void AnimationHandle::setURL(const QUrl& url) {
if (_url != url) {
_animation = DependencyManager::get<AnimationCache>()->getAnimation(_url = url);
_animation->ensureLoading();
QObject::connect(_animation.data(), &Resource::onRefresh, this, &AnimationHandle::clearJoints);
_jointMappings.clear();
}
}
void AnimationHandle::setPriority(float priority) {
if (_priority == priority) {
return;
}
if (isRunning()) {
_rig->removeRunningAnimation(getAnimationHandlePointer());
if (priority < _priority) {
replaceMatchingPriorities(priority);
}
_priority = priority;
_rig->addRunningAnimation(getAnimationHandlePointer());
} else {
_priority = priority;
}
}
void AnimationHandle::setStartAutomatically(bool startAutomatically) {
if (startAutomatically && !isRunning()) {
// Start before setting _animationLoop value so that code in setRunning() is executed
start();
}
_animationLoop.setStartAutomatically(startAutomatically);
}
void AnimationHandle::setMaskedJoints(const QStringList& maskedJoints) {
_maskedJoints = maskedJoints;
_jointMappings.clear();
}
void AnimationHandle::setRunning(bool running, bool doRestoreJoints) {
if (running && isRunning() && (getFadePerSecond() >= 0.0f)) {
// if we're already running, this is the same as a restart -- unless we're fading out.
setCurrentFrame(getFirstFrame());
return;
}
_animationLoop.setRunning(running);
if (isRunning()) {
if (!_rig->isRunningAnimation(getAnimationHandlePointer())) {
_rig->addRunningAnimation(getAnimationHandlePointer());
}
} else {
_rig->removeRunningAnimation(getAnimationHandlePointer());
if (doRestoreJoints) {
restoreJoints();
}
replaceMatchingPriorities(0.0f);
}
emit runningChanged(isRunning());
}
AnimationHandle::AnimationHandle(RigPointer rig) :
QObject(rig.get()),
_rig(rig),
_priority(1.0f),
_fade(0.0f),
_fadePerSecond(0.0f)
{
}
AnimationDetails AnimationHandle::getAnimationDetails() const {
AnimationDetails details(_role, _url, getFPS(), _priority, getLoop(), getHold(),
getStartAutomatically(), getFirstFrame(), getLastFrame(), isRunning(), getCurrentFrame());
return details;
}
void AnimationHandle::setAnimationDetails(const AnimationDetails& details) {
setRole(details.role);
setURL(details.url);
setFPS(details.fps);
setPriority(details.priority);
setLoop(details.loop);
setHold(details.hold);
setStartAutomatically(details.startAutomatically);
setFirstFrame(details.firstFrame);
setLastFrame(details.lastFrame);
setRunning(details.running);
setCurrentFrame(details.currentFrame);
// NOTE: AnimationDetails doesn't support maskedJoints
//setMaskedJoints(const QStringList& maskedJoints);
}
void AnimationHandle::setJointMappings(QVector<int> jointMappings) {
_jointMappings = jointMappings;
}
QVector<int> AnimationHandle::getJointMappings() {
if (_jointMappings.isEmpty()) {
QVector<FBXJoint> animationJoints = _animation->getGeometry().joints;
for (int i = 0; i < animationJoints.count(); i++) {
_jointMappings.append(_rig->indexOfJoint(animationJoints.at(i).name));
}
}
return _jointMappings;
}
void AnimationHandle::simulate(float deltaTime) {
if (!_animation || !_animation->isLoaded()) {
return;
}
_animationLoop.simulate(deltaTime);
if (getJointMappings().isEmpty()) {
qDebug() << "AnimationHandle::simulate -- _jointMappings.isEmpty()";
return;
}
// // update the joint mappings if necessary/possible
// if (_jointMappings.isEmpty()) {
// if (_model && _model->isActive()) {
// _jointMappings = _model->getGeometry()->getJointMappings(_animation);
// }
// if (_jointMappings.isEmpty()) {
// return;
// }
// if (!_maskedJoints.isEmpty()) {
// const FBXGeometry& geometry = _model->getGeometry()->getFBXGeometry();
// for (int i = 0; i < _jointMappings.size(); i++) {
// int& mapping = _jointMappings[i];
// if (mapping != -1 && _maskedJoints.contains(geometry.joints.at(mapping).name)) {
// mapping = -1;
// }
// }
// }
// }
const FBXGeometry& animationGeometry = _animation->getGeometry();
if (animationGeometry.animationFrames.isEmpty()) {
stop();
return;
}
if (_animationLoop.getMaxFrameIndexHint() != animationGeometry.animationFrames.size()) {
_animationLoop.setMaxFrameIndexHint(animationGeometry.animationFrames.size());
}
// blend between the closest two frames
applyFrame(getCurrentFrame());
}
void AnimationHandle::applyFrame(float currentFrame) {
if (!_animation || !_animation->isLoaded()) {
return;
}
const FBXGeometry& animationGeometry = _animation->getGeometry();
int frameCount = animationGeometry.animationFrames.size();
const FBXAnimationFrame& floorFrame = animationGeometry.animationFrames.at((int)glm::floor(currentFrame) % frameCount);
const FBXAnimationFrame& ceilFrame = animationGeometry.animationFrames.at((int)glm::ceil(currentFrame) % frameCount);
float frameFraction = glm::fract(currentFrame);
for (int i = 0; i < _jointMappings.size(); i++) {
int mapping = _jointMappings.at(i);
if (mapping != -1) { // allow missing bones
_rig->setJointRotationInConstrainedFrame(mapping,
safeMix(floorFrame.rotations.at(i),
ceilFrame.rotations.at(i),
frameFraction),
_priority,
_mix);
// This isn't working.
// glm::vec3 floorTranslationPart = floorFrame.translations.at(i) * (1.0f - frameFraction);
// glm::vec3 ceilTranslationPart = ceilFrame.translations.at(i) * frameFraction;
// glm::vec3 floorCeilFraction = floorTranslationPart + ceilTranslationPart;
// glm::vec3 defaultTrans = _rig->getJointDefaultTranslationInConstrainedFrame(i);
// glm::vec3 mixedTranslation = floorCeilFraction * (1.0f - _mix) + defaultTrans * _mix;
// _rig->setJointTranslation(mapping, true, mixedTranslation, _priority);
}
}
}
void AnimationHandle::replaceMatchingPriorities(float newPriority) {
for (int i = 0; i < _jointMappings.size(); i++) {
int mapping = _jointMappings.at(i);
if (mapping != -1) {
if (_priority == _rig->getJointAnimatinoPriority(mapping)) {
_rig->setJointAnimatinoPriority(mapping, newPriority);
}
}
}
}
void AnimationHandle::restoreJoints() {
for (int i = 0; i < _jointMappings.size(); i++) {
int mapping = _jointMappings.at(i);
if (mapping != -1) {
_rig->restoreJointRotation(mapping, 1.0f, _rig->getJointAnimatinoPriority(mapping));
_rig->restoreJointTranslation(mapping, 1.0f, _rig->getJointAnimatinoPriority(mapping));
}
}
}

View file

@ -1,138 +0,0 @@
//
// AnimationHandle.h
// libraries/animation/src/
//
// Created by Andrzej Kapolka on 10/18/13.
// Copyright 2013 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#ifndef hifi_AnimationHandle_h
#define hifi_AnimationHandle_h
#include <QObject>
#include <QString>
#include <QStringList>
#include <QUrl>
#include <QVector>
#include "AnimationCache.h"
#include "AnimationLoop.h"
#include "Rig.h"
class AnimationHandle;
class Model;
typedef std::shared_ptr<AnimationHandle> AnimationHandlePointer;
typedef std::weak_ptr<AnimationHandle> WeakAnimationHandlePointer;
inline uint qHash(const std::shared_ptr<AnimationHandle>& a, uint seed) {
// return qHash(a.get(), seed);
AnimationHandle* strongRef = a ? a.get() : nullptr;
return qHash(strongRef, seed);
}
inline uint qHash(const std::weak_ptr<AnimationHandle>& a, uint seed) {
AnimationHandlePointer strongPointer = a.lock();
AnimationHandle* strongRef = strongPointer ? strongPointer.get() : nullptr;
return qHash(strongRef, seed);
}
// inline uint qHash(const WeakAnimationHandlePointer& handle, uint seed) {
// return qHash(handle.data(), seed);
// }
/// Represents a handle to a model animation. I.e., an Animation in use by a given Rig.
class AnimationHandle : public QObject, public std::enable_shared_from_this<AnimationHandle> {
Q_OBJECT
public:
AnimationHandle(RigPointer rig);
AnimationHandlePointer getAnimationHandlePointer() { return shared_from_this(); }
void setRole(const QString& role) { _role = role; }
const QString& getRole() const { return _role; }
void setURL(const QUrl& url);
const QUrl& getURL() const { return _url; }
void setPriority(float priority);
float getPriority() const { return _priority; }
void setMix(float mix) { _mix = mix; }
void setFade(float fade) { _fade = fade; }
float getFade() const { return _fade; }
void setFadePerSecond(float fadePerSecond) { _fadePerSecond = fadePerSecond; }
float getFadePerSecond() const { return _fadePerSecond; }
void setMaskedJoints(const QStringList& maskedJoints);
const QStringList& getMaskedJoints() const { return _maskedJoints; }
void setFPS(float fps) { _animationLoop.setFPS(fps); }
float getFPS() const { return _animationLoop.getFPS(); }
void setLoop(bool loop) { _animationLoop.setLoop(loop); }
bool getLoop() const { return _animationLoop.getLoop(); }
void setHold(bool hold) { _animationLoop.setHold(hold); }
bool getHold() const { return _animationLoop.getHold(); }
void setStartAutomatically(bool startAutomatically);
bool getStartAutomatically() const { return _animationLoop.getStartAutomatically(); }
void setFirstFrame(float firstFrame) { _animationLoop.setFirstFrame(firstFrame); }
float getFirstFrame() const { return _animationLoop.getFirstFrame(); }
void setLastFrame(float lastFrame) { _animationLoop.setLastFrame(lastFrame); }
float getLastFrame() const { return _animationLoop.getLastFrame(); }
void setRunning(bool running, bool restoreJoints = true);
bool isRunning() const { return _animationLoop.getRunning(); }
void setCurrentFrame(float currentFrame) { _animationLoop.setCurrentFrame(currentFrame); }
float getCurrentFrame() const { return _animationLoop.getCurrentFrame(); }
AnimationDetails getAnimationDetails() const;
void setAnimationDetails(const AnimationDetails& details);
void setJointMappings(QVector<int> jointMappings);
QVector<int> getJointMappings(); // computing if necessary
void simulate(float deltaTime);
void applyFrame(float currentFrame);
void replaceMatchingPriorities(float newPriority);
void restoreJoints();
void clearJoints() { _jointMappings.clear(); }
signals:
void runningChanged(bool running);
public slots:
void start() { setRunning(true); }
void stop() { setRunning(false); _fadePerSecond = _fade = 0.0f; }
private:
RigPointer _rig;
AnimationPointer _animation;
QString _role;
QUrl _url;
float _priority;
float _mix; // How much of this animation to blend against what is already there. 1.0 sets to just this animation.
float _fade; // How far are we into full strength. 0.0 uses none of this animation, 1.0 (the max) is as much as possible.
float _fadePerSecond; // How fast should _fade change? +1.0 means _fade is increasing to 1.0 in 1 second. Negative is fading out.
QStringList _maskedJoints;
QVector<int> _jointMappings;
AnimationLoop _animationLoop;
};
#endif // hifi_AnimationHandle_h

View file

@ -1,122 +0,0 @@
//
// AvatarRig.cpp
// libraries/animation/src/
//
// Created by SethAlves on 2015-7-22.
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#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) {
bool rightHand = (jointIndex == _rightHandJointIndex);
int elbowJointIndex = rightHand ? _rightElbowJointIndex : _leftElbowJointIndex;
int shoulderJointIndex = rightHand ? _rightShoulderJointIndex : _leftShoulderJointIndex;
// this algorithm is from sample code from sixense
if (elbowJointIndex == -1 || shoulderJointIndex == -1) {
return;
}
glm::vec3 shoulderPosition;
if (!getJointPosition(shoulderJointIndex, shoulderPosition)) {
return;
}
// precomputed lengths
float upperArmLength = _jointStates[elbowJointIndex].getDistanceToParent() * scale;
float lowerArmLength = _jointStates[jointIndex].getDistanceToParent() * scale;
// first set wrist position
glm::vec3 wristPosition = position;
glm::vec3 shoulderToWrist = wristPosition - shoulderPosition;
float distanceToWrist = glm::length(shoulderToWrist);
// prevent gimbal lock
if (distanceToWrist > upperArmLength + lowerArmLength - EPSILON) {
distanceToWrist = upperArmLength + lowerArmLength - EPSILON;
shoulderToWrist = glm::normalize(shoulderToWrist) * distanceToWrist;
wristPosition = shoulderPosition + shoulderToWrist;
}
// cosine of angle from upper arm to hand vector
float cosA = (upperArmLength * upperArmLength + distanceToWrist * distanceToWrist - lowerArmLength * lowerArmLength) /
(2 * upperArmLength * distanceToWrist);
float mid = upperArmLength * cosA;
float height = sqrt(upperArmLength * upperArmLength + mid * mid - 2 * upperArmLength * mid * cosA);
// direction of the elbow
glm::vec3 handNormal = glm::cross(rotation * glm::vec3(0.0f, 1.0f, 0.0f), shoulderToWrist); // elbow rotating with wrist
glm::vec3 relaxedNormal = glm::cross(glm::vec3(0.0f, 1.0f, 0.0f), shoulderToWrist); // elbow pointing straight down
const float NORMAL_WEIGHT = 0.5f;
glm::vec3 finalNormal = glm::mix(relaxedNormal, handNormal, NORMAL_WEIGHT);
if (rightHand ? (finalNormal.y > 0.0f) : (finalNormal.y < 0.0f)) {
finalNormal.y = 0.0f; // dont allow elbows to point inward (y is vertical axis)
}
glm::vec3 tangent = glm::normalize(glm::cross(shoulderToWrist, finalNormal));
// ik solution
glm::vec3 elbowPosition = shoulderPosition + glm::normalize(shoulderToWrist) * mid - tangent * height;
glm::vec3 forwardVector(rightHand ? -1.0f : 1.0f, 0.0f, 0.0f);
glm::quat shoulderRotation = rotationBetween(forwardVector, elbowPosition - shoulderPosition);
setJointRotationInBindFrame(shoulderJointIndex, shoulderRotation, priority);
setJointRotationInBindFrame(elbowJointIndex,
rotationBetween(shoulderRotation * forwardVector, wristPosition - elbowPosition) *
shoulderRotation, priority);
setJointRotationInBindFrame(jointIndex, rotation, priority);
}
void AvatarRig::setJointTranslation(int index, bool valid, const glm::vec3& translation, float priority) {
if (index != -1 && index < _jointStates.size()) {
JointState& state = _jointStates[index];
if (valid) {
state.setTranslation(translation, priority);
} else {
state.restoreTranslation(1.0f, priority);
}
}
}
void AvatarRig::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];
if (valid) {
state.setRotationInConstrainedFrame(rotation, priority);
state.setTranslation(translation, priority);
} else {
state.restoreRotation(1.0f, priority);
state.restoreTranslation(1.0f, priority);
}
}
}

View file

@ -1,33 +0,0 @@
//
// AvatarRig.h
// libraries/animation/src/
//
// Created by SethAlves on 2015-7-22.
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#ifndef hifi_AvatarRig_h
#define hifi_AvatarRig_h
#include <QObject>
#include "Rig.h"
class AvatarRig : public Rig {
Q_OBJECT
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);
virtual void setJointState(int index, bool valid, const glm::quat& rotation, const glm::vec3& translation, float priority);
};
#endif // hifi_AvatarRig_h

View file

@ -1,43 +0,0 @@
//
// EntityRig.cpp
// libraries/animation/src/
//
// Created by SethAlves on 2015-7-22.
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#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];
if (valid) {
state.setRotationInConstrainedFrame(rotation, priority);
// state.setTranslation(translation, priority);
} else {
state.restoreRotation(1.0f, priority);
// state.restoreTranslation(1.0f, priority);
}
}
}

View file

@ -1,30 +0,0 @@
//
// EntityRig.h
// libraries/animation/src/
//
// Created by SethAlves on 2015-7-22.
// Copyright 2015 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#ifndef hifi_EntityRig_h
#define hifi_EntityRig_h
#include <QObject>
#include "Rig.h"
class EntityRig : public Rig {
Q_OBJECT
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);
};
#endif // hifi_EntityRig_h

View file

@ -1,228 +0,0 @@
//
// JointState.cpp
// libraries/animation/src/
//
// Created by Andrzej Kapolka on 10/18/13.
// Copyright 2013 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#include <glm/gtx/norm.hpp>
#include <QThreadPool>
#include <SharedUtil.h>
#include "JointState.h"
JointState::~JointState() {
}
void JointState::copyState(const JointState& other) {
_transformChanged = other._transformChanged;
_transform = other._transform;
_rotationIsValid = other._rotationIsValid;
_rotation = other._rotation;
_rotationInConstrainedFrame = other._rotationInConstrainedFrame;
_positionInParentFrame = other._positionInParentFrame;
_distanceToParent = other._distanceToParent;
_animationPriority = other._animationPriority;
_name = other._name;
_isFree = other._isFree;
_parentIndex = other._parentIndex;
_defaultRotation = other._defaultRotation;
_defaultTranslation = other._defaultTranslation;
_inverseDefaultRotation = other._inverseDefaultRotation;
_translation = other._translation;
_preRotation = other._preRotation;
_postRotation = other._postRotation;
_preTransform = other._preTransform;
_postTransform = other._postTransform;
_inverseBindRotation = other._inverseBindRotation;
}
JointState::JointState(const FBXJoint& joint) {
_rotationInConstrainedFrame = joint.rotation;
_name = joint.name;
_isFree = joint.isFree;
_parentIndex = joint.parentIndex;
_translation = joint.translation;
_defaultRotation = joint.rotation;
_defaultTranslation = _translation;
_inverseDefaultRotation = joint.inverseDefaultRotation;
_preRotation = joint.preRotation;
_postRotation = joint.postRotation;
_preTransform = joint.preTransform;
_postTransform = joint.postTransform;
_inverseBindRotation = joint.inverseBindRotation;
}
void JointState::buildConstraint() {
}
glm::quat JointState::getRotation() const {
if (!_rotationIsValid) {
const_cast<JointState*>(this)->_rotation = extractRotation(_transform);
const_cast<JointState*>(this)->_rotationIsValid = true;
}
return _rotation;
}
void JointState::initTransform(const glm::mat4& parentTransform) {
_unitsScale = extractScale(parentTransform);
computeTransform(parentTransform);
_positionInParentFrame = glm::inverse(extractRotation(parentTransform)) * (extractTranslation(_transform) - extractTranslation(parentTransform));
_distanceToParent = glm::length(_positionInParentFrame);
}
void JointState::computeTransform(const glm::mat4& parentTransform, bool parentTransformChanged, bool synchronousRotationCompute) {
if (!parentTransformChanged && !_transformChanged) {
return;
}
glm::quat rotationInParentFrame = _preRotation * _rotationInConstrainedFrame * _postRotation;
glm::mat4 transformInParentFrame = _preTransform * glm::mat4_cast(rotationInParentFrame) * _postTransform;
glm::mat4 newTransform = parentTransform * glm::translate(_translation) * transformInParentFrame;
if (newTransform != _transform) {
_transform = newTransform;
_transformChanged = true;
_rotationIsValid = false;
}
}
glm::quat JointState::getRotationInBindFrame() const {
return getRotation() * _inverseBindRotation;
}
glm::quat JointState::getRotationInParentFrame() const {
return _preRotation * _rotationInConstrainedFrame * _postRotation;
}
void JointState::restoreRotation(float fraction, float priority) {
if (priority == _animationPriority || _animationPriority == 0.0f) {
setRotationInConstrainedFrameInternal(safeMix(_rotationInConstrainedFrame, _defaultRotation, fraction));
_animationPriority = 0.0f;
}
}
void JointState::restoreTranslation(float fraction, float priority) {
if (priority == _animationPriority || _animationPriority == 0.0f) {
_translation = _translation * (1.0f - fraction) + _defaultTranslation * fraction;
_animationPriority = 0.0f;
}
}
void JointState::setRotationInBindFrame(const glm::quat& rotation, float priority) {
// rotation is from bind- to model-frame
if (priority >= _animationPriority) {
glm::quat targetRotation = _rotationInConstrainedFrame * glm::inverse(getRotation()) * rotation * glm::inverse(_inverseBindRotation);
setRotationInConstrainedFrameInternal(targetRotation);
_animationPriority = priority;
}
}
void JointState::setRotationInModelFrame(const glm::quat& rotationInModelFrame, float priority) {
// rotation is from bind- to model-frame
if (priority >= _animationPriority) {
glm::quat parentRotation = computeParentRotation();
// R = Rp * Rpre * r * Rpost
// R' = Rp * Rpre * r' * Rpost
// r' = (Rp * Rpre)^ * R' * Rpost^
glm::quat targetRotation = glm::inverse(parentRotation * _preRotation) * rotationInModelFrame * glm::inverse(_postRotation);
_rotationInConstrainedFrame = glm::normalize(targetRotation);
_transformChanged = true;
_animationPriority = priority;
}
}
void JointState::clearTransformTranslation() {
_transform[3][0] = 0.0f;
_transform[3][1] = 0.0f;
_transform[3][2] = 0.0f;
_transformChanged = true;
}
void JointState::applyRotationDelta(const glm::quat& delta, float priority) {
// NOTE: delta is in model-frame
if (priority < _animationPriority || delta == glm::quat()) {
return;
}
_animationPriority = priority;
glm::quat targetRotation = _rotationInConstrainedFrame * glm::inverse(getRotation()) * delta * getRotation();
setRotationInConstrainedFrameInternal(targetRotation);
}
/// Applies delta rotation to joint but mixes a little bit of the default pose as well.
/// This helps keep an IK solution stable.
void JointState::mixRotationDelta(const glm::quat& delta, float mixFactor, float priority) {
// NOTE: delta is in model-frame
if (priority < _animationPriority) {
return;
}
_animationPriority = priority;
glm::quat targetRotation = _rotationInConstrainedFrame * glm::inverse(getRotation()) * delta * getRotation();
if (mixFactor > 0.0f && mixFactor <= 1.0f) {
targetRotation = safeMix(targetRotation, _defaultRotation, mixFactor);
}
setRotationInConstrainedFrameInternal(targetRotation);
}
glm::quat JointState::computeParentRotation() const {
// R = Rp * Rpre * r * Rpost
// Rp = R * (Rpre * r * Rpost)^
return getRotation() * glm::inverse(_preRotation * _rotationInConstrainedFrame * _postRotation);
}
void JointState::setRotationInConstrainedFrame(glm::quat targetRotation, float priority, float mix) {
if (priority >= _animationPriority || _animationPriority == 0.0f) {
auto rotation = (mix == 1.0f) ? targetRotation : safeMix(getRotationInConstrainedFrame(), targetRotation, mix);
setRotationInConstrainedFrameInternal(rotation);
_animationPriority = priority;
}
}
void JointState::setTranslation(const glm::vec3& translation, float priority) {
if (priority >= _animationPriority || _animationPriority == 0.0f) {
_translation = translation / _unitsScale;
_transformChanged = true;
_animationPriority = priority;
}
}
void JointState::setRotationInConstrainedFrameInternal(const glm::quat& targetRotation) {
if (_rotationInConstrainedFrame != targetRotation) {
glm::quat parentRotation = computeParentRotation();
_rotationInConstrainedFrame = targetRotation;
_transformChanged = true;
// R' = Rp * Rpre * r' * Rpost
_rotation = parentRotation * _preRotation * _rotationInConstrainedFrame * _postRotation;
}
}
bool JointState::rotationIsDefault(const glm::quat& rotation, float tolerance) const {
glm::quat defaultRotation = _defaultRotation;
return glm::abs(rotation.x - defaultRotation.x) < tolerance &&
glm::abs(rotation.y - defaultRotation.y) < tolerance &&
glm::abs(rotation.z - defaultRotation.z) < tolerance &&
glm::abs(rotation.w - defaultRotation.w) < tolerance;
}
bool JointState::translationIsDefault(const glm::vec3& translation, float tolerance) const {
return glm::distance(_defaultTranslation * _unitsScale, translation) < tolerance;
}
glm::quat JointState::getDefaultRotationInParentFrame() const {
// NOTE: the result is constant and could be cached
return _preRotation * _defaultRotation * _postRotation;
}
glm::vec3 JointState::getDefaultTranslationInConstrainedFrame() const {
return _defaultTranslation * _unitsScale;
}

View file

@ -1,149 +0,0 @@
//
// JointState.h
// libraries/animation/src/
//
// Created by Andrzej Kapolka on 10/18/13.
// Copyright 2013 High Fidelity, Inc.
//
// Distributed under the Apache License, Version 2.0.
// See the accompanying file LICENSE or http://www.apache.org/licenses/LICENSE-2.0.html
//
#ifndef hifi_JointState_h
#define hifi_JointState_h
#include <glm/glm.hpp>
#include <glm/gtx/quaternion.hpp>
#include <glm/gtx/transform.hpp>
#include <FBXReader.h>
#include <GLMHelpers.h>
#include <NumericalConstants.h>
const float DEFAULT_PRIORITY = 3.0f;
class JointState {
public:
JointState() {}
JointState(const JointState& other) { copyState(other); }
JointState(const FBXJoint& joint);
~JointState();
JointState& operator=(const JointState& other) { copyState(other); return *this; }
void copyState(const JointState& state);
void buildConstraint();
void initTransform(const glm::mat4& parentTransform);
// if synchronousRotationCompute is true, then _transform is still computed synchronously,
// but _rotation will be asynchronously extracted
void computeTransform(const glm::mat4& parentTransform, bool parentTransformChanged = true, bool synchronousRotationCompute = false);
const glm::mat4& getTransform() const { return _transform; }
void resetTransformChanged() { _transformChanged = false; }
bool getTransformChanged() const { return _transformChanged; }
glm::quat getRotation() const;
glm::vec3 getPosition() const { return extractTranslation(_transform); }
/// \return rotation from bind to model frame
glm::quat getRotationInBindFrame() const;
glm::quat getRotationInParentFrame() const;
const glm::vec3& getPositionInParentFrame() const { return _positionInParentFrame; }
float getDistanceToParent() const { return _distanceToParent; }
int getParentIndex() const { return _parentIndex; }
/// \param delta is in the model-frame
void applyRotationDelta(const glm::quat& delta, float priority = 1.0f);
/// Applies delta rotation to joint but mixes a little bit of the default pose as well.
/// This helps keep an IK solution stable.
/// \param delta rotation change in model-frame
/// \param mixFactor fraction in range [0,1] of how much default pose to blend in (0 is none, 1 is all)
/// \param priority priority level of this animation blend
void mixRotationDelta(const glm::quat& delta, float mixFactor, float priority = 1.0f);
/// Blends a fraciton of default pose into joint rotation.
/// \param fraction fraction in range [0,1] of how much default pose to blend in (0 is none, 1 is all)
/// \param priority priority level of this animation blend
void restoreRotation(float fraction, float priority);
void restoreTranslation(float fraction, float priority);
/// \param rotation is from bind- to model-frame
/// computes and sets new _rotationInConstrainedFrame
/// NOTE: the JointState's model-frame transform/rotation are NOT updated!
void setRotationInBindFrame(const glm::quat& rotation, float priority);
/// \param rotationInModelRame is in model-frame
/// computes and sets new _rotationInConstrainedFrame to match rotationInModelFrame
/// NOTE: the JointState's model-frame transform/rotation are NOT updated!
void setRotationInModelFrame(const glm::quat& rotationInModelFrame, float priority);
void setTranslation(const glm::vec3& translation, float priority);
void setRotationInConstrainedFrame(glm::quat targetRotation, float priority, float mix = 1.0f);
const glm::quat& getRotationInConstrainedFrame() const { return _rotationInConstrainedFrame; }
bool rotationIsDefault(const glm::quat& rotation, float tolerance = EPSILON) const;
bool translationIsDefault(const glm::vec3& translation, float tolerance = EPSILON) const;
glm::quat getDefaultRotationInParentFrame() const;
glm::vec3 getDefaultTranslationInConstrainedFrame() const;
void clearTransformTranslation();
/// \return parent model-frame rotation
// (used to keep _rotation consistent when modifying _rotationInWorldFrame directly)
glm::quat computeParentRotation() const;
void setTransform(const glm::mat4& transform) { _transform = transform; }
glm::vec3 getTranslation() const { return _translation * _unitsScale; }
const glm::mat4& getPreTransform() const { return _preTransform; }
const glm::mat4& getPostTransform() const { return _postTransform; }
const glm::quat& getPreRotation() const { return _preRotation; }
const glm::quat& getPostRotation() const { return _postRotation; }
const glm::quat& getDefaultRotation() const { return _defaultRotation; }
glm::vec3 getDefaultTranslation() const { return _defaultTranslation * _unitsScale; }
glm::vec3 getUnscaledDefaultTranslation() const { return _defaultTranslation; }
const glm::quat& getInverseDefaultRotation() const { return _inverseDefaultRotation; }
const QString& getName() const { return _name; }
bool getIsFree() const { return _isFree; }
float getAnimationPriority() const { return _animationPriority; }
void setAnimationPriority(float priority) { _animationPriority = priority; }
private:
void setRotationInConstrainedFrameInternal(const glm::quat& targetRotation);
/// debug helper function
void loadBindRotation();
bool _transformChanged {true};
bool _rotationIsValid {false};
glm::vec3 _positionInParentFrame {0.0f}; // only changes when the Model is scaled
float _animationPriority {0.0f}; // the priority of the animation affecting this joint
float _distanceToParent {0.0f};
glm::mat4 _transform; // joint- to model-frame
glm::quat _rotation; // joint- to model-frame
glm::quat _rotationInConstrainedFrame; // rotation in frame where angular constraints would be applied
glm::quat _defaultRotation; // Not necessarilly bind rotation. See FBXJoint transform/bindTransform
glm::quat _inverseDefaultRotation;
glm::vec3 _defaultTranslation;
glm::vec3 _translation;
QString _name;
int _parentIndex;
bool _isFree;
glm::quat _preRotation;
glm::quat _postRotation;
glm::mat4 _preTransform;
glm::mat4 _postTransform;
glm::quat _inverseBindRotation;
glm::vec3 _unitsScale{1.0f, 1.0f, 1.0f};
};
#endif // hifi_JointState_h

File diff suppressed because it is too large Load diff

View file

@ -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__
@ -39,16 +17,13 @@
#include <QObject>
#include <QMutex>
#include <QScriptValue>
#include "JointState.h" // We might want to change this (later) to something that doesn't depend on gpu, fbx and model. -HRS
#include <vector>
#include <JointData.h>
#include "AnimNode.h"
#include "AnimNodeLoader.h"
#include "SimpleMovingAverage.h"
class AnimationHandle;
typedef std::shared_ptr<AnimationHandle> AnimationHandlePointer;
class Rig;
typedef std::shared_ptr<Rig> RigPointer;
@ -66,12 +41,9 @@ public:
float leanForward = 0.0f; // degrees
float torsoTwist = 0.0f; // degrees
bool enableLean = false;
glm::quat worldHeadOrientation = glm::quat();
glm::quat localHeadOrientation = glm::quat();
float localHeadPitch = 0.0f; // degrees
float localHeadYaw = 0.0f; // degrees
float localHeadRoll = 0.0f; // degrees
glm::vec3 localHeadPosition = glm::vec3();
glm::quat worldHeadOrientation = glm::quat(); // world space (-z forward)
glm::quat rigHeadOrientation = glm::quat(); // rig space (-z forward)
glm::vec3 rigHeadPosition = glm::vec3(); // rig space
bool isInHMD = false;
int leanJointIndex = -1;
int neckJointIndex = -1;
@ -91,162 +63,186 @@ public:
struct HandParameters {
bool isLeftEnabled;
bool isRightEnabled;
glm::vec3 leftPosition = glm::vec3();
glm::quat leftOrientation = glm::quat();
glm::vec3 rightPosition = glm::vec3();
glm::quat rightOrientation = glm::quat();
glm::vec3 leftPosition = glm::vec3(); // rig space
glm::quat leftOrientation = glm::quat(); // rig space (z forward)
glm::vec3 rightPosition = glm::vec3(); // rig space
glm::quat rightOrientation = glm::quat(); // rig space (z forward)
float leftTrigger = 0.0f;
float rightTrigger = 0.0f;
};
virtual ~Rig() {}
RigPointer getRigPointer() { return shared_from_this(); }
AnimationHandlePointer createAnimationHandle();
void removeAnimationHandle(const AnimationHandlePointer& handle);
bool removeRunningAnimation(AnimationHandlePointer animationHandle);
void addRunningAnimation(AnimationHandlePointer animationHandle);
bool isRunningAnimation(AnimationHandlePointer animationHandle);
bool isRunningRole(const QString& role); // There can be multiple animations per role, so this is more general than isRunningAnimation.
const QList<AnimationHandlePointer>& getRunningAnimations() const { return _runningAnimations; }
void deleteAnimations();
void destroyAnimGraph();
const QList<AnimationHandlePointer>& getAnimationHandles() const { return _animationHandles; }
void startAnimation(const QString& url, float fps = 30.0f, float priority = 1.0f, bool loop = false,
bool hold = false, float firstFrame = 0.0f, float lastFrame = FLT_MAX, const QStringList& maskedJoints = QStringList());
void stopAnimation(const QString& url);
void startAnimationByRole(const QString& role, const QString& url = QString(), float fps = 30.0f,
float priority = 1.0f, bool loop = false, bool hold = false, float firstFrame = 0.0f,
float lastFrame = FLT_MAX, const QStringList& maskedJoints = QStringList());
void stopAnimationByRole(const QString& role);
AnimationHandlePointer addAnimationByRole(const QString& role, const QString& url = QString(), float fps = 30.0f,
float priority = 1.0f, bool loop = false, bool hold = false, float firstFrame = 0.0f,
float lastFrame = FLT_MAX, const QStringList& maskedJoints = QStringList(), bool startAutomatically = false);
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(); }
int indexOfJoint(const QString& jointName);
void overrideAnimation(const QString& url, float fps, bool loop, float firstFrame, float lastFrame);
void restoreAnimation();
QStringList getAnimationRoles() const;
void overrideRoleAnimation(const QString& role, const QString& url, float fps, bool loop, float firstFrame, float lastFrame);
void restoreRoleAnimation(const QString& role);
void prefetchAnimation(const QString& url);
void initJointTransforms(glm::mat4 rootTransform);
void clearJointTransformTranslation(int jointIndex);
void reset(const QVector<FBXJoint>& fbxJoints);
void initJointStates(const FBXGeometry& geometry, const glm::mat4& modelOffset);
void reset(const FBXGeometry& geometry);
bool jointStatesEmpty();
int getJointStateCount() const;
int indexOfJoint(const QString& jointName) const;
void setModelOffset(const glm::mat4& modelOffsetMat);
// geometry space
bool getJointStateRotation(int index, glm::quat& rotation) const;
// geometry space
bool getJointStateTranslation(int index, glm::vec3& translation) const;
void applyJointRotationDelta(int jointIndex, const glm::quat& delta, float priority);
JointState getJointState(int jointIndex) const; // XXX
void clearJointState(int index);
void clearJointStates();
void clearJointAnimationPriority(int index);
float getJointAnimatinoPriority(int index);
void setJointAnimatinoPriority(int index, float newPriority);
virtual void setJointState(int index, bool valid, const glm::quat& rotation, const glm::vec3& translation,
float priority) = 0;
virtual void setJointTranslation(int index, bool valid, const glm::vec3& translation, float priority) {}
// geometry space
void setJointState(int index, bool valid, const glm::quat& rotation, const glm::vec3& translation, float priority);
// geometry space
void setJointTranslation(int index, bool valid, const glm::vec3& translation, float priority);
// geometry space
void setJointRotation(int index, bool valid, const glm::quat& rotation, float priority);
// legacy
void restoreJointRotation(int index, float fraction, float priority);
void restoreJointTranslation(int index, float fraction, float priority);
// if translation and rotation is identity, position will be in rig space
bool getJointPositionInWorldFrame(int jointIndex, glm::vec3& position,
glm::vec3 translation, glm::quat rotation) const;
// rig space
bool getJointPosition(int jointIndex, glm::vec3& position) const;
// if rotation is identity, result will be in rig space
bool getJointRotationInWorldFrame(int jointIndex, glm::quat& result, const glm::quat& rotation) const;
// geometry space
bool getJointRotation(int jointIndex, glm::quat& rotation) const;
// geometry space
bool getJointTranslation(int jointIndex, glm::vec3& translation) const;
// legacy
bool getJointCombinedRotation(int jointIndex, glm::quat& result, const glm::quat& rotation) const;
// rig space
glm::mat4 getJointTransform(int jointIndex) const;
glm::mat4 getJointVisibleTransform(int jointIndex) const;
void setJointVisibleTransform(int jointIndex, glm::mat4 newTransform);
// Start or stop animations as needed.
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);
// legacy
void inverseKinematics(int endIndex, glm::vec3 targetPosition, const glm::quat& targetRotation, float priority,
const QVector<int>& freeLineage, glm::mat4 rootTransform);
// legacy
bool restoreJointPosition(int jointIndex, float fraction, float priority, const QVector<int>& freeLineage);
// legacy
float getLimbLength(int jointIndex, const QVector<int>& freeLineage,
const glm::vec3 scale, const QVector<FBXJoint>& fbxJoints) const;
// legacy
glm::quat setJointRotationInBindFrame(int jointIndex, const glm::quat& rotation, float priority);
// legacy
glm::vec3 getJointDefaultTranslationInConstrainedFrame(int jointIndex);
// legacy
glm::quat setJointRotationInConstrainedFrame(int jointIndex, glm::quat targetRotation,
float priority, float mix = 1.0f);
// legacy
bool getJointRotationInConstrainedFrame(int jointIndex, glm::quat& rotOut) const;
// legacy
glm::quat getJointDefaultRotationInParentFrame(int jointIndex);
// legacy
void clearJointStatePriorities();
virtual void updateJointState(int index, glm::mat4 rootTransform) = 0;
void setEnableRig(bool isEnabled) { _enableRig = isEnabled; }
bool getEnableRig() const { return _enableRig; }
void setEnableAnimGraph(bool isEnabled) { _enableAnimGraph = isEnabled; }
bool getEnableAnimGraph() const { return _enableAnimGraph; }
void updateFromHeadParameters(const HeadParameters& params, float dt);
void updateFromEyeParameters(const EyeParameters& params);
void updateFromHandParameters(const HandParameters& params, float dt);
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; }
bool disableHands {false}; // should go away with rig animation (and Rig::inverseKinematics)
QScriptValue addAnimationStateHandler(QScriptValue handler, QScriptValue propertiesList);
void removeAnimationStateHandler(QScriptValue handler);
void animationStateHandlerResult(int identifier, QScriptValue result);
bool getModelOffset(glm::vec3& modelOffsetOut) const;
// rig space
bool getModelRegistrationPoint(glm::vec3& modelRegistrationPointOut) const;
const glm::vec3& getEyesInRootFrame() const { return _eyesInRootFrame; }
// rig space
AnimPose getAbsoluteDefaultPose(int index) const;
// rig space
const AnimPoseVec& getAbsoluteDefaultPoses() const;
void copyJointsIntoJointData(QVector<JointData>& jointDataVec) const;
void copyJointsFromJointData(const QVector<JointData>& jointDataVec);
void computeAvatarBoundingCapsule(const FBXGeometry& geometry, float& radiusOut, float& heightOut, glm::vec3& offsetOut) const;
protected:
bool isIndexValid(int index) const { return _animSkeleton && index >= 0 && index < _animSkeleton->getNumJoints(); }
void updateAnimationStateHandlers();
void applyOverridePoses();
void buildAbsoluteRigPoses(const AnimPoseVec& relativePoses, AnimPoseVec& absolutePosesOut);
void updateLeanJoint(int index, float leanSideways, float leanForward, float torsoTwist);
void updateNeckJoint(int index, const HeadParameters& params);
void computeHeadNeckAnimVars(const AnimPose& hmdPose, glm::vec3& headPositionOut, glm::quat& headOrientationOut,
glm::vec3& neckPositionOut, glm::quat& neckOrientationOut) const;
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;
void computeEyesInRootFrame(const AnimPoseVec& poses);
QVector<JointState> _jointStates;
int _rootJointIndex = -1;
AnimPose _modelOffset; // model to rig space
AnimPose _geometryOffset; // geometry to model space (includes unit offset & fst offsets)
int _leftHandJointIndex = -1;
int _leftElbowJointIndex = -1;
int _leftShoulderJointIndex = -1;
AnimPoseVec _relativePoses; // geometry space relative to parent.
AnimPoseVec _absolutePoses; // rig space, not relative to parent.
AnimPoseVec _overridePoses; // geometry space relative to parent.
std::vector<bool> _overrideFlags;
int _rightHandJointIndex = -1;
int _rightElbowJointIndex = -1;
int _rightShoulderJointIndex = -1;
AnimPoseVec _absoluteDefaultPoses; // rig space, not relative to parent.
QList<AnimationHandlePointer> _animationHandles;
QList<AnimationHandlePointer> _runningAnimations;
glm::mat4 _geometryToRigTransform;
glm::mat4 _rigToGeometryTransform;
int _rootJointIndex { -1 };
int _leftHandJointIndex { -1 };
int _leftElbowJointIndex { -1 };
int _leftShoulderJointIndex { -1 };
int _rightHandJointIndex { -1 };
int _rightElbowJointIndex { -1 };
int _rightShoulderJointIndex { -1 };
bool _enableRig = false;
bool _enableAnimGraph = false;
glm::vec3 _lastFront;
glm::vec3 _lastPosition;
glm::vec3 _lastVelocity;
glm::vec3 _eyesInRootFrame { Vectors::ZERO };
QUrl _animGraphURL;
std::shared_ptr<AnimNode> _animNode;
std::shared_ptr<AnimSkeleton> _animSkeleton;
std::unique_ptr<AnimNodeLoader> _animLoader;
@ -256,18 +252,28 @@ public:
Turn,
Move
};
RigRole _state = RigRole::Idle;
RigRole _desiredState = RigRole::Idle;
float _desiredStateAge = 0.0f;
float _leftHandOverlayAlpha = 0.0f;
float _rightHandOverlayAlpha = 0.0f;
RigRole _state { RigRole::Idle };
RigRole _desiredState { RigRole::Idle };
float _desiredStateAge { 0.0f };
enum class UserAnimState {
None = 0,
A,
B
};
UserAnimState _userAnimState { UserAnimState::None };
QString _currentUserAnimURL;
float _leftHandOverlayAlpha { 0.0f };
float _rightHandOverlayAlpha { 0.0f };
SimpleMovingAverage _averageForwardSpeed{ 10 };
SimpleMovingAverage _averageLateralSpeed{ 10 };
SimpleMovingAverage _averageForwardSpeed { 10 };
SimpleMovingAverage _averageLateralSpeed { 10 };
std::map<QString, AnimNode::Pointer> _origRoleAnimations;
std::vector<AnimNode::Pointer> _prefetchedAnimations;
private:
QMap<int, StateHandler> _stateHandlers;
int _nextStateHandlerId {0};
int _nextStateHandlerId { 0 };
QMutex _stateMutex;
};

View file

@ -46,6 +46,7 @@ typedef unsigned long long quint64;
#include <QtScript/QScriptable>
#include <QReadWriteLock>
#include <JointData.h>
#include <NLPacket.h>
#include <Node.h>
#include <RegisteredMetaTypes.h>
@ -131,7 +132,6 @@ enum KeyState {
class QDataStream;
class AttachmentData;
class JointData;
class Transform;
using TransformPointer = std::shared_ptr<Transform>;
@ -434,14 +434,6 @@ private:
};
Q_DECLARE_METATYPE(AvatarData*)
class JointData {
public:
glm::quat rotation;
bool rotationSet = false;
glm::vec3 translation;
bool translationSet = false;
};
QJsonValue toJsonValue(const JointData& joint);
JointData jointDataFromJsonValue(const QJsonValue& q);

View file

@ -43,7 +43,7 @@
#include "RenderablePolyLineEntityItem.h"
#include "EntitiesRendererLogging.h"
#include "AddressManager.h"
#include "EntityRig.h"
#include <Rig.h>
EntityTreeRenderer::EntityTreeRenderer(bool wantScripts, AbstractViewStateInterface* viewState,
AbstractScriptingServicesInterface* scriptingServices) :
@ -422,7 +422,7 @@ Model* EntityTreeRenderer::allocateModel(const QString& url, const QString& coll
return model;
}
model = new Model(std::make_shared<EntityRig>());
model = new Model(std::make_shared<Rig>());
model->init();
model->setURL(QUrl(url));
model->setCollisionModelURL(QUrl(collisionUrl));
@ -455,7 +455,7 @@ Model* EntityTreeRenderer::updateModel(Model* original, const QString& newUrl, c
}
// create the model and correctly initialize it with the new url
model = new Model(std::make_shared<EntityRig>());
model = new Model(std::make_shared<Rig>());
model->init();
model->setURL(QUrl(newUrl));
model->setCollisionModelURL(QUrl(collisionUrl));

View file

@ -13,6 +13,7 @@
#include <QObject>
#include <QByteArray>
#include <QtConcurrent/QtConcurrentRun>
#include <glm/gtx/transform.hpp>
#if defined(__GNUC__) && !defined(__clang__)
#pragma GCC diagnostic push

View file

@ -224,6 +224,7 @@ void ModelEntityItem::getAnimationFrame(bool& newFrame,
if (myAnimation && myAnimation->isLoaded()) {
const QVector<FBXAnimationFrame>& frames = myAnimation->getFramesReference(); // NOTE: getFrames() is too heavy
auto& fbxJoints = myAnimation->getGeometry().joints;
int frameCount = frames.size();
if (frameCount > 0) {
@ -244,7 +245,7 @@ void ModelEntityItem::getAnimationFrame(bool& newFrame,
for (int j = 0; j < _jointMapping.size(); j++) {
int index = _jointMapping[j];
if (index != -1 && index < rotations.size()) {
_lastKnownFrameDataRotations[j] = rotations[index];
_lastKnownFrameDataRotations[j] = fbxJoints[index].preRotation * rotations[index];
}
if (index != -1 && index < translations.size()) {
_lastKnownFrameDataTranslations[j] = translations[index];

View file

@ -750,13 +750,6 @@ FBXGeometry* FBXReader::extractFBXGeometry(const QVariantHash& mapping, const QS
model.preRotation = glm::quat(glm::radians(preRotation));
model.rotation = glm::quat(glm::radians(rotation));
model.postRotation = glm::quat(glm::radians(postRotation));
if (geometry.applicationName.startsWith("Blender")) {
// blender puts the jointOffset in the wrong place.
model.preRotation = model.rotation;
model.rotation = glm::quat();
}
model.postTransform = glm::translate(-rotationPivot) * glm::translate(scaleOffset) *
glm::translate(scalePivot) * glm::scale(scale) * glm::translate(-scalePivot);
// NOTE: angles from the FBX file are in degrees

View file

@ -45,7 +45,7 @@ PacketVersion versionForPacketType(PacketType packetType) {
case PacketType::AvatarData:
case PacketType::BulkAvatarData:
default:
return 16;
return 17;
}
}

View file

@ -153,28 +153,12 @@ void AnimDebugDraw::shutdown() {
}
}
void AnimDebugDraw::addSkeleton(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPose& rootPose, const glm::vec4& color) {
_skeletons[key] = SkeletonInfo(skeleton, rootPose, color);
void AnimDebugDraw::addAbsolutePoses(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPoseVec& poses, const AnimPose& rootPose, const glm::vec4& color) {
_absolutePoses[key] = PosesInfo(skeleton, poses, rootPose, color);
}
void AnimDebugDraw::removeSkeleton(const std::string& key) {
_skeletons.erase(key);
}
void AnimDebugDraw::addAnimNode(const std::string& key, AnimNode::ConstPointer animNode, const AnimPose& rootPose, const glm::vec4& color) {
_animNodes[key] = AnimNodeInfo(animNode, rootPose, color);
}
void AnimDebugDraw::removeAnimNode(const std::string& key) {
_animNodes.erase(key);
}
void AnimDebugDraw::addPoses(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPoseVec& poses, const AnimPose& rootPose, const glm::vec4& color) {
_poses[key] = PosesInfo(skeleton, poses, rootPose, color);
}
void AnimDebugDraw::removePoses(const std::string& key) {
_poses.erase(key);
void AnimDebugDraw::removeAbsolutePoses(const std::string& key) {
_absolutePoses.erase(key);
}
static const uint32_t red = toRGBA(255, 0, 0, 255);
@ -338,31 +322,8 @@ void AnimDebugDraw::update() {
// figure out how many verts we will need.
int numVerts = 0;
for (auto& iter : _skeletons) {
AnimSkeleton::ConstPointer& skeleton = std::get<0>(iter.second);
numVerts += skeleton->getNumJoints() * VERTICES_PER_BONE;
for (int i = 0; i < skeleton->getNumJoints(); i++) {
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
numVerts += VERTICES_PER_LINK;
}
}
}
for (auto& iter : _animNodes) {
AnimNode::ConstPointer& animNode = std::get<0>(iter.second);
auto poses = animNode->getPosesInternal();
numVerts += poses.size() * VERTICES_PER_BONE;
auto skeleton = animNode->getSkeleton();
for (size_t i = 0; i < poses.size(); i++) {
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
numVerts += VERTICES_PER_LINK;
}
}
}
for (auto& iter : _poses) {
for (auto& iter : _absolutePoses) {
AnimSkeleton::ConstPointer& skeleton = std::get<0>(iter.second);
numVerts += skeleton->getNumJoints() * VERTICES_PER_BONE;
for (int i = 0; i < skeleton->getNumJoints(); i++) {
@ -379,106 +340,29 @@ void AnimDebugDraw::update() {
auto myAvatarMarkerMap = DebugDraw::getInstance().getMyAvatarMarkerMap();
numVerts += myAvatarMarkerMap.size() * VERTICES_PER_BONE;
// allocate verts!
data._vertexBuffer->resize(sizeof(Vertex) * numVerts);
Vertex* verts = (Vertex*)data._vertexBuffer->editData();
Vertex* v = verts;
for (auto& iter : _skeletons) {
// draw absolute poses
for (auto& iter : _absolutePoses) {
AnimSkeleton::ConstPointer& skeleton = std::get<0>(iter.second);
AnimPose rootPose = std::get<1>(iter.second);
int hipsIndex = skeleton->nameToJointIndex("Hips");
if (hipsIndex >= 0) {
rootPose.trans -= skeleton->getRelativeBindPose(hipsIndex).trans;
}
glm::vec4 color = std::get<2>(iter.second);
for (int i = 0; i < skeleton->getNumJoints(); i++) {
AnimPose pose = skeleton->getAbsoluteBindPose(i);
const float radius = BONE_RADIUS / (pose.scale.x * rootPose.scale.x);
// draw bone
addBone(rootPose, pose, radius, v);
// draw link to parent
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
assert(parentIndex < skeleton->getNumJoints());
AnimPose parentPose = skeleton->getAbsoluteBindPose(parentIndex);
addLink(rootPose, pose, parentPose, radius, color, v);
}
}
}
for (auto& iter : _animNodes) {
AnimNode::ConstPointer& animNode = std::get<0>(iter.second);
AnimPose rootPose = std::get<1>(iter.second);
if (animNode->_skeleton) {
int hipsIndex = animNode->_skeleton->nameToJointIndex("Hips");
if (hipsIndex >= 0) {
rootPose.trans -= animNode->_skeleton->getRelativeBindPose(hipsIndex).trans;
}
}
glm::vec4 color = std::get<2>(iter.second);
auto poses = animNode->getPosesInternal();
auto skeleton = animNode->getSkeleton();
std::vector<AnimPose> absAnimPose;
absAnimPose.resize(skeleton->getNumJoints());
for (size_t i = 0; i < poses.size(); i++) {
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
absAnimPose[i] = absAnimPose[parentIndex] * poses[i];
} else {
absAnimPose[i] = poses[i];
}
const float radius = BONE_RADIUS / (absAnimPose[i].scale.x * rootPose.scale.x);
addBone(rootPose, absAnimPose[i], radius, v);
if (parentIndex >= 0) {
assert((size_t)parentIndex < poses.size());
// draw line to parent
addLink(rootPose, absAnimPose[i], absAnimPose[parentIndex], radius, color, v);
}
}
}
for (auto& iter : _poses) {
AnimSkeleton::ConstPointer& skeleton = std::get<0>(iter.second);
AnimPoseVec& poses = std::get<1>(iter.second);
AnimPoseVec& absPoses = std::get<1>(iter.second);
AnimPose rootPose = std::get<2>(iter.second);
int hipsIndex = skeleton->nameToJointIndex("Hips");
if (hipsIndex >= 0) {
rootPose.trans -= skeleton->getRelativeBindPose(hipsIndex).trans;
}
glm::vec4 color = std::get<3>(iter.second);
std::vector<AnimPose> absAnimPose;
absAnimPose.resize(skeleton->getNumJoints());
for (int i = 0; i < skeleton->getNumJoints(); i++) {
const AnimPose& pose = poses[i];
const float radius = BONE_RADIUS / (pose.scale.x * rootPose.scale.x);
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
absAnimPose[i] = absAnimPose[parentIndex] * pose;
} else {
absAnimPose[i] = pose;
}
const float radius = BONE_RADIUS / (absPoses[i].scale.x * rootPose.scale.x);
// draw bone
addBone(rootPose, absAnimPose[i], radius, v);
addBone(rootPose, absPoses[i], radius, v);
// draw link to parent
auto parentIndex = skeleton->getParentIndex(i);
if (parentIndex >= 0) {
assert(parentIndex < skeleton->getNumJoints());
addLink(rootPose, absAnimPose[i], absAnimPose[parentIndex], radius, color, v);
addLink(rootPose, absPoses[i], absPoses[parentIndex], radius, color, v);
}
}
}

View file

@ -29,17 +29,8 @@ public:
void shutdown();
// draw a skeleton bind pose
void addSkeleton(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPose& rootPose, const glm::vec4& color);
void removeSkeleton(const std::string& key);
// draw the interal poses for a specific animNode
void addAnimNode(const std::string& key, AnimNode::ConstPointer animNode, const AnimPose& rootPose, const glm::vec4& color);
void removeAnimNode(const std::string& key);
// draw a set of poses with a skeleton
void addPoses(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPoseVec& poses, const AnimPose& rootPose, const glm::vec4& color);
void removePoses(const std::string& key);
void addAbsolutePoses(const std::string& key, AnimSkeleton::ConstPointer skeleton, const AnimPoseVec& poses, const AnimPose& rootPose, const glm::vec4& color);
void removeAbsolutePoses(const std::string& key);
void update();
@ -50,13 +41,9 @@ protected:
static gpu::PipelinePointer _pipeline;
typedef std::tuple<AnimSkeleton::ConstPointer, AnimPose, glm::vec4> SkeletonInfo;
typedef std::tuple<AnimNode::ConstPointer, AnimPose, glm::vec4> AnimNodeInfo;
typedef std::tuple<AnimSkeleton::ConstPointer, AnimPoseVec, AnimPose, glm::vec4> PosesInfo;
std::unordered_map<std::string, SkeletonInfo> _skeletons;
std::unordered_map<std::string, AnimNodeInfo> _animNodes;
std::unordered_map<std::string, PosesInfo> _poses;
std::unordered_map<std::string, PosesInfo> _absolutePoses;
// no copies
AnimDebugDraw(const AnimDebugDraw&) = delete;

View file

@ -22,7 +22,6 @@
#include <ViewFrustum.h>
#include "AbstractViewStateInterface.h"
#include "AnimationHandle.h"
#include "Model.h"
#include "MeshPartPayload.h"
@ -88,6 +87,8 @@ void Model::setScale(const glm::vec3& scale) {
_scaledToFit = false;
}
const float METERS_PER_MILLIMETER = 0.01f;
void Model::setScaleInternal(const glm::vec3& scale) {
if (glm::distance(_scale, scale) > METERS_PER_MILLIMETER) {
_scale = scale;
@ -103,24 +104,12 @@ 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);
_rig->setModelOffset(modelOffset);
}
void Model::init() {
@ -129,14 +118,13 @@ void Model::init() {
void Model::reset() {
if (_geometry && _geometry->isLoaded()) {
const FBXGeometry& geometry = _geometry->getFBXGeometry();
_rig->reset(geometry.joints);
_rig->reset(geometry);
}
}
bool Model::updateGeometry() {
PROFILE_RANGE(__FUNCTION__);
bool needFullUpdate = false;
bool needToRebuild = false;
if (!_geometry || !_geometry->isLoaded()) {
// geometry is not ready
@ -145,17 +133,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());
@ -178,26 +159,11 @@ 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);
int rootJointIndex = geometry.rootJointIndex;
int leftHandJointIndex = geometry.leftHandJointIndex;
int leftElbowJointIndex = leftHandJointIndex >= 0 ? geometry.joints.at(leftHandJointIndex).parentIndex : -1;
int leftShoulderJointIndex = leftElbowJointIndex >= 0 ? geometry.joints.at(leftElbowJointIndex).parentIndex : -1;
int rightHandJointIndex = geometry.rightHandJointIndex;
int rightElbowJointIndex = rightHandJointIndex >= 0 ? geometry.joints.at(rightHandJointIndex).parentIndex : -1;
int rightShoulderJointIndex = rightElbowJointIndex >= 0 ? geometry.joints.at(rightElbowJointIndex).parentIndex : -1;
_rig->initJointStates(states, parentTransform,
rootJointIndex,
leftHandJointIndex,
leftElbowJointIndex,
leftShoulderJointIndex,
rightHandJointIndex,
rightElbowJointIndex,
rightShoulderJointIndex);
_rig->initJointStates(geometry, modelOffset);
}
bool Model::findRayIntersectionAgainstSubMeshes(const glm::vec3& origin, const glm::vec3& direction, float& distance,
@ -838,6 +804,7 @@ void Blender::run() {
const float NORMAL_COEFFICIENT_SCALE = 0.01f;
for (int i = 0, n = qMin(_blendshapeCoefficients.size(), mesh.blendshapes.size()); i < n; i++) {
float vertexCoefficient = _blendshapeCoefficients.at(i);
const float EPSILON = 0.0001f;
if (vertexCoefficient < EPSILON) {
continue;
}
@ -965,9 +932,7 @@ void Model::updateRig(float deltaTime, glm::mat4 parentTransform) {
}
void Model::simulateInternal(float deltaTime) {
// update the world space transforms for all joints
const FBXGeometry& geometry = _geometry->getFBXGeometry();
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset);
updateRig(deltaTime, parentTransform);
}
void Model::updateClusterMatrices() {
@ -1028,22 +993,10 @@ 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;
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset) * geometry.offset;
glm::mat4 parentTransform = glm::scale(_scale) * glm::translate(_offset);
_rig->inverseKinematics(endIndex, targetPosition, targetRotation, priority, freeLineage, parentTransform);
}
@ -1102,11 +1055,7 @@ void Model::setGeometry(const QSharedPointer<NetworkGeometry>& newGeometry) {
void Model::deleteGeometry() {
_blendedVertexBuffers.clear();
_meshStates.clear();
if (_rig) {
_rig->clearJointStates();
_rig->deleteAnimations();
_rig->destroyAnimGraph();
}
_rig->destroyAnimGraph();
_blendedBlendshapeCoefficients.clear();
}
@ -1154,8 +1103,6 @@ void Model::segregateMeshGroups() {
const FBXGeometry& geometry = networkGeometry->getFBXGeometry();
const std::vector<std::unique_ptr<NetworkMesh>>& networkMeshes = networkGeometry->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()) {

View file

@ -28,10 +28,9 @@
#include <render/Scene.h>
#include <Transform.h>
#include "AnimationHandle.h"
#include "GeometryCache.h"
#include "JointState.h"
#include "TextureCache.h"
#include "Rig.h"
class AbstractViewStateInterface;
class QScriptEngine;
@ -274,7 +273,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();
@ -283,18 +282,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
@ -318,7 +305,6 @@ protected:
private:
void deleteGeometry();
QVector<JointState> createJointStates(const FBXGeometry& geometry);
void initJointTransforms();
QSharedPointer<NetworkGeometry> _collisionGeometry;

View file

@ -10,7 +10,7 @@
//
#include "GLMHelpers.h"
#include <glm/gtc/matrix_transform.hpp>
#include "NumericalConstants.h"
const vec3 Vectors::UNIT_X{ 1.0f, 0.0f, 0.0f };
@ -34,6 +34,7 @@ const vec3& Vectors::UP = Vectors::UNIT_Y;
const vec3& Vectors::FRONT = Vectors::UNIT_NEG_Z;
const quat Quaternions::IDENTITY{ 1.0f, 0.0f, 0.0f, 0.0f };
const quat Quaternions::Y_180{ 0.0f, 0.0f, 1.0f, 0.0f };
// Safe version of glm::mix; based on the code in Nick Bobick's article,
// http://www.gamasutra.com/features/19980703/quaternions_01.htm (via Clyde,
@ -276,6 +277,18 @@ glm::quat extractRotation(const glm::mat4& matrix, bool assumeOrthogonal) {
0.5f * sqrtf(z2) * (upper[0][1] >= upper[1][0] ? 1.0f : -1.0f)));
}
glm::quat glmExtractRotation(const glm::mat4& matrix) {
glm::vec3 scale = extractScale(matrix);
float maxScale = std::max(std::max(scale.x, scale.y), scale.z);
if (maxScale > 1.01f || maxScale <= 0.99f) {
// quat_cast doesn't work so well with scaled matrices, so cancel it out.
glm::mat4 tmp = glm::scale(matrix, 1.0f / scale);
return glm::normalize(glm::quat_cast(tmp));
} else {
return glm::normalize(glm::quat_cast(matrix));
}
}
glm::vec3 extractScale(const glm::mat4& matrix) {
return glm::vec3(glm::length(matrix[0]), glm::length(matrix[1]), glm::length(matrix[2]));
}

View file

@ -58,6 +58,7 @@ glm::quat safeMix(const glm::quat& q1, const glm::quat& q2, float alpha);
class Quaternions {
public:
static const quat IDENTITY;
static const quat Y_180;
};
class Vectors {
@ -131,6 +132,7 @@ glm::vec3 extractTranslation(const glm::mat4& matrix);
void setTranslation(glm::mat4& matrix, const glm::vec3& translation);
glm::quat extractRotation(const glm::mat4& matrix, bool assumeOrthogonal = false);
glm::quat glmExtractRotation(const glm::mat4& matrix);
glm::vec3 extractScale(const glm::mat4& matrix);

View file

@ -0,0 +1,18 @@
#ifndef hifi_JointData_h
#define hifi_JointData_h
#include <glm/glm.hpp>
#include <glm/gtc/quaternion.hpp>
// Used by the avatar mixer to describe a single joint
// These are relative to their parent and translations are in meters
class JointData {
public:
glm::quat rotation;
bool rotationSet = false;
glm::vec3 translation; // meters
bool translationSet = false;
};
#endif

View file

@ -44,24 +44,27 @@
#include "FBXReader.h"
#include "OBJReader.h"
#include "AvatarRig.h" // We might later test Rig vs AvatarRig separately, but for now, we're concentrating on the main use case.
#include <Rig.h>
#include "RigTests.h"
static void reportJoint(int index, JointState joint) { // Handy for debugging
static void reportJoint(RigPointer rig, int index) { // Handy for debugging
std::cout << "\n";
std::cout << index << " " << joint.getName().toUtf8().data() << "\n";
std::cout << " pos:" << joint.getPosition() << "/" << joint.getPositionInParentFrame() << " from " << joint.getParentIndex() << "\n";
std::cout << " rot:" << safeEulerAngles(joint.getRotation()) << "/" << safeEulerAngles(joint.getRotationInParentFrame()) << "/" << safeEulerAngles(joint.getRotationInBindFrame()) << "\n";
std::cout << index << " " << rig->getAnimSkeleton()->getJointName(index).toUtf8().data() << "\n";
glm::vec3 pos;
rig->getJointPosition(index, pos);
glm::quat rot;
rig->getJointRotation(index, rot);
std::cout << " pos:" << pos << "\n";
std::cout << " rot:" << safeEulerAngles(rot) << "\n";
std::cout << "\n";
}
static void reportByName(RigPointer rig, const QString& name) {
int jointIndex = rig->indexOfJoint(name);
reportJoint(jointIndex, rig->getJointState(jointIndex));
reportJoint(rig, jointIndex);
}
static void reportAll(RigPointer rig) {
for (int i = 0; i < rig->getJointStateCount(); i++) {
JointState joint = rig->getJointState(i);
reportJoint(i, joint);
reportJoint(rig, i);
}
}
static void reportSome(RigPointer rig) {
@ -88,17 +91,11 @@ void RigTests::initTestCase() {
#endif
QVERIFY((bool)geometry);
QVector<JointState> jointStates;
for (int i = 0; i < geometry->joints.size(); ++i) {
JointState state(geometry->joints[i]);
jointStates.append(state);
}
_rig = std::make_shared<AvatarRig>();
_rig->initJointStates(jointStates, glm::mat4(), 0, 41, 40, 39, 17, 16, 15); // FIXME? get by name? do we really want to exclude the shoulder blades?
_rig = std::make_shared<Rig>();
_rig->initJointStates(*geometry, glm::mat4());
std::cout << "Rig is ready " << geometry->joints.count() << " joints " << std::endl;
reportAll(_rig);
}
}
void RigTests::initialPoseArmsDown() {
reportSome(_rig);