mirror of
https://github.com/overte-org/overte.git
synced 2025-04-14 01:48:59 +02:00
Added hand state machines to AnimGraph.
* Application: Forward trigger values to the MyAvatar's PalmData * SkeletonModel: Pass PalmData to Rig via updateRigFromHandData() this is more explicit then the Rig::inverseKinematics methods. * AnimNodeLoader & AnimOverlay: add support for LeftHand and RightHand bone sets * Rig::updateRigFromHandData() read the triggers and set stateMachine trigger vars * avatar.json - udpated with new hand state machine with temporary animations
This commit is contained in:
parent
2385331075
commit
90f46ba2c8
11 changed files with 525 additions and 219 deletions
|
@ -2868,8 +2868,8 @@ void Application::update(float deltaTime) {
|
|||
UserInputMapper::PoseValue leftHand = userInputMapper->getPoseState(UserInputMapper::LEFT_HAND);
|
||||
UserInputMapper::PoseValue rightHand = userInputMapper->getPoseState(UserInputMapper::RIGHT_HAND);
|
||||
Hand* hand = DependencyManager::get<AvatarManager>()->getMyAvatar()->getHand();
|
||||
setPalmData(hand, leftHand, deltaTime, LEFT_HAND_INDEX);
|
||||
setPalmData(hand, rightHand, deltaTime, RIGHT_HAND_INDEX);
|
||||
setPalmData(hand, leftHand, deltaTime, LEFT_HAND_INDEX, userInputMapper->getActionState(UserInputMapper::LEFT_HAND_CLICK));
|
||||
setPalmData(hand, rightHand, deltaTime, RIGHT_HAND_INDEX, userInputMapper->getActionState(UserInputMapper::RIGHT_HAND_CLICK));
|
||||
if (Menu::getInstance()->isOptionChecked(MenuOption::HandMouseInput)) {
|
||||
emulateMouse(hand, userInputMapper->getActionState(UserInputMapper::LEFT_HAND_CLICK),
|
||||
userInputMapper->getActionState(UserInputMapper::SHIFT), LEFT_HAND_INDEX);
|
||||
|
@ -4970,7 +4970,7 @@ mat4 Application::getHMDSensorPose() const {
|
|||
return mat4();
|
||||
}
|
||||
|
||||
void Application::setPalmData(Hand* hand, UserInputMapper::PoseValue pose, float deltaTime, int index) {
|
||||
void Application::setPalmData(Hand* hand, UserInputMapper::PoseValue pose, float deltaTime, int index, float triggerValue) {
|
||||
PalmData* palm;
|
||||
bool foundHand = false;
|
||||
for (size_t j = 0; j < hand->getNumPalms(); j++) {
|
||||
|
@ -5040,6 +5040,7 @@ void Application::setPalmData(Hand* hand, UserInputMapper::PoseValue pose, float
|
|||
palm->setTipVelocity(glm::vec3(0.0f));
|
||||
}
|
||||
palm->setTipPosition(newTipPosition);
|
||||
palm->setTrigger(triggerValue);
|
||||
}
|
||||
|
||||
void Application::emulateMouse(Hand* hand, float click, float shift, int index) {
|
||||
|
|
|
@ -485,7 +485,7 @@ private:
|
|||
|
||||
void update(float deltaTime);
|
||||
|
||||
void setPalmData(Hand* hand, UserInputMapper::PoseValue pose, float deltaTime, int index);
|
||||
void setPalmData(Hand* hand, UserInputMapper::PoseValue pose, float deltaTime, int index, float triggerValue);
|
||||
void emulateMouse(Hand* hand, float click, float shift, int index);
|
||||
|
||||
// Various helper functions called during update()
|
||||
|
|
|
@ -1298,8 +1298,8 @@ void MyAvatar::initAnimGraph() {
|
|||
//
|
||||
// or run a local web-server
|
||||
// python -m SimpleHTTPServer&
|
||||
// auto graphUrl = QUrl("http://localhost:8000/avatar.json");
|
||||
auto graphUrl = QUrl("https://gist.githubusercontent.com/hyperlogic/e58e0a24cc341ad5d060/raw/8f824da2908fd89ad1befadd1d8f5d7b3b6efa66/ik-avatar.json");
|
||||
auto graphUrl = QUrl("http://localhost:8000/avatar.json");
|
||||
//auto graphUrl = QUrl("https://gist.githubusercontent.com/hyperlogic/e58e0a24cc341ad5d060/raw/8f824da2908fd89ad1befadd1d8f5d7b3b6efa66/ik-avatar.json");
|
||||
_rig->initAnimGraph(graphUrl, _skeletonModel.getGeometry()->getFBXGeometry());
|
||||
}
|
||||
|
||||
|
|
|
@ -96,6 +96,17 @@ void SkeletonModel::initJointStates(QVector<JointState> states) {
|
|||
emit skeletonLoaded();
|
||||
}
|
||||
|
||||
static const PalmData* getPalmWithIndex(Hand* hand, int index) {
|
||||
const PalmData* palm = nullptr;
|
||||
for (size_t j = 0; j < hand->getNumPalms(); j++) {
|
||||
if (hand->getPalms()[j].getSixenseID() == index) {
|
||||
palm = &(hand->getPalms()[j]);
|
||||
break;
|
||||
}
|
||||
}
|
||||
return palm;
|
||||
}
|
||||
|
||||
const float PALM_PRIORITY = DEFAULT_PRIORITY;
|
||||
// Called within Model::simulate call, below.
|
||||
void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
|
||||
|
@ -108,34 +119,60 @@ void SkeletonModel::updateRig(float deltaTime, glm::mat4 parentTransform) {
|
|||
MyAvatar* myAvatar = static_cast<MyAvatar*>(_owningAvatar);
|
||||
const FBXGeometry& geometry = _geometry->getFBXGeometry();
|
||||
|
||||
Rig::HeadParameters params;
|
||||
params.modelRotation = getRotation();
|
||||
params.modelTranslation = getTranslation();
|
||||
params.enableLean = qApp->getAvatarUpdater()->isHMDMode() && !myAvatar->getStandingHMDSensorMode();
|
||||
params.leanSideways = head->getFinalLeanSideways();
|
||||
params.leanForward = head->getFinalLeanForward();
|
||||
params.torsoTwist = head->getTorsoTwist();
|
||||
params.localHeadOrientation = head->getFinalOrientationInLocalFrame();
|
||||
params.localHeadPitch = head->getFinalPitch();
|
||||
params.localHeadYaw = head->getFinalYaw();
|
||||
params.localHeadRoll = head->getFinalRoll();
|
||||
params.isInHMD = qApp->getAvatarUpdater()->isHMDMode();
|
||||
Rig::HeadParameters headParams;
|
||||
headParams.modelRotation = getRotation();
|
||||
headParams.modelTranslation = getTranslation();
|
||||
headParams.enableLean = qApp->getAvatarUpdater()->isHMDMode() && !myAvatar->getStandingHMDSensorMode();
|
||||
headParams.leanSideways = head->getFinalLeanSideways();
|
||||
headParams.leanForward = head->getFinalLeanForward();
|
||||
headParams.torsoTwist = head->getTorsoTwist();
|
||||
headParams.localHeadOrientation = head->getFinalOrientationInLocalFrame();
|
||||
headParams.localHeadPitch = head->getFinalPitch();
|
||||
headParams.localHeadYaw = head->getFinalYaw();
|
||||
headParams.localHeadRoll = head->getFinalRoll();
|
||||
headParams.isInHMD = qApp->getAvatarUpdater()->isHMDMode();
|
||||
|
||||
// get HMD position from sensor space into world space, and back into model space
|
||||
glm::mat4 worldToModel = glm::inverse(createMatFromQuatAndPos(myAvatar->getOrientation(), myAvatar->getPosition()));
|
||||
glm::vec3 yAxis(0.0f, 1.0f, 0.0f);
|
||||
glm::vec3 hmdPosition = glm::angleAxis((float)M_PI, yAxis) * transformPoint(worldToModel * myAvatar->getSensorToWorldMatrix(), myAvatar->getHMDSensorPosition());
|
||||
params.localHeadPosition = hmdPosition;
|
||||
headParams.localHeadPosition = hmdPosition;
|
||||
|
||||
params.worldHeadOrientation = head->getFinalOrientationInWorldFrame();
|
||||
params.eyeLookAt = head->getLookAtPosition();
|
||||
params.eyeSaccade = head->getSaccade();
|
||||
params.leanJointIndex = geometry.leanJointIndex;
|
||||
params.neckJointIndex = geometry.neckJointIndex;
|
||||
params.leftEyeJointIndex = geometry.leftEyeJointIndex;
|
||||
params.rightEyeJointIndex = geometry.rightEyeJointIndex;
|
||||
headParams.worldHeadOrientation = head->getFinalOrientationInWorldFrame();
|
||||
headParams.eyeLookAt = head->getLookAtPosition();
|
||||
headParams.eyeSaccade = head->getSaccade();
|
||||
headParams.leanJointIndex = geometry.leanJointIndex;
|
||||
headParams.neckJointIndex = geometry.neckJointIndex;
|
||||
headParams.leftEyeJointIndex = geometry.leftEyeJointIndex;
|
||||
headParams.rightEyeJointIndex = geometry.rightEyeJointIndex;
|
||||
|
||||
_rig->updateFromHeadParameters(headParams);
|
||||
|
||||
Rig::HandParameters handParams;
|
||||
|
||||
// this is sooo getto
|
||||
const PalmData* leftPalm = getPalmWithIndex(myAvatar->getHand(), LEFT_HAND_INDEX);
|
||||
if (leftPalm && leftPalm->isActive()) {
|
||||
handParams.isLeftEnabled = true;
|
||||
handParams.leftPosition = leftPalm->getRawPosition();
|
||||
handParams.leftOrientation = leftPalm->getRawRotation();
|
||||
handParams.leftTrigger = leftPalm->getTrigger();
|
||||
} else {
|
||||
handParams.isLeftEnabled = false;
|
||||
}
|
||||
|
||||
const PalmData* rightPalm = getPalmWithIndex(myAvatar->getHand(), RIGHT_HAND_INDEX);
|
||||
if (rightPalm && rightPalm->isActive()) {
|
||||
handParams.isRightEnabled = true;
|
||||
handParams.rightPosition = rightPalm->getRawPosition();
|
||||
handParams.rightOrientation = rightPalm->getRawRotation();
|
||||
handParams.rightTrigger = rightPalm->getTrigger();
|
||||
} else {
|
||||
handParams.isRightEnabled = false;
|
||||
}
|
||||
|
||||
_rig->updateFromHandParameters(handParams);
|
||||
|
||||
_rig->updateFromHeadParameters(params);
|
||||
} else {
|
||||
// This is a little more work than we really want.
|
||||
//
|
||||
|
|
|
@ -342,7 +342,7 @@ void AnimInverseKinematics::initConstraints() {
|
|||
// compute corresponding absolute poses
|
||||
int numJoints = (int)_defaultRelativePoses.size();
|
||||
AnimPoseVec absolutePoses;
|
||||
absolutePoses.reserve(numJoints);
|
||||
absolutePoses.resize(numJoints);
|
||||
for (int i = 0; i < numJoints; ++i) {
|
||||
int parentIndex = _skeleton->getParentIndex(i);
|
||||
if (parentIndex < 0) {
|
||||
|
|
|
@ -172,7 +172,12 @@ static AnimNode::Pointer loadNode(const QJsonObject& jsonObj, const QUrl& jsonUr
|
|||
qCCritical(animation) << "AnimNodeLoader, bad object in \"children\", id =" << id << ", url =" << jsonUrl.toDisplayString();
|
||||
return nullptr;
|
||||
}
|
||||
node->addChild(loadNode(childValue.toObject(), jsonUrl));
|
||||
AnimNode::Pointer child = loadNode(childValue.toObject(), jsonUrl);
|
||||
if (child) {
|
||||
node->addChild(child);
|
||||
} else {
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
if ((animNodeTypeToProcessFunc(type))(node, dataObj, id, jsonUrl)) {
|
||||
|
@ -232,13 +237,15 @@ static const char* boneSetStrings[AnimOverlay::NumBoneSets] = {
|
|||
"fullBody",
|
||||
"upperBody",
|
||||
"lowerBody",
|
||||
"rightArm",
|
||||
"leftArm",
|
||||
"rightArm",
|
||||
"aboveTheHead",
|
||||
"belowTheHead",
|
||||
"headOnly",
|
||||
"spineOnly",
|
||||
"empty"
|
||||
"empty",
|
||||
"leftHand",
|
||||
"rightHand"
|
||||
};
|
||||
|
||||
static AnimOverlay::BoneSet stringToBoneSetEnum(const QString& str) {
|
||||
|
|
|
@ -26,12 +26,14 @@ void AnimOverlay::buildBoneSet(BoneSet boneSet) {
|
|||
case FullBodyBoneSet: buildFullBodyBoneSet(); break;
|
||||
case UpperBodyBoneSet: buildUpperBodyBoneSet(); break;
|
||||
case LowerBodyBoneSet: buildLowerBodyBoneSet(); break;
|
||||
case RightArmBoneSet: buildRightArmBoneSet(); break;
|
||||
case LeftArmBoneSet: buildLeftArmBoneSet(); break;
|
||||
case RightArmBoneSet: buildRightArmBoneSet(); break;
|
||||
case AboveTheHeadBoneSet: buildAboveTheHeadBoneSet(); break;
|
||||
case BelowTheHeadBoneSet: buildBelowTheHeadBoneSet(); break;
|
||||
case HeadOnlyBoneSet: buildHeadOnlyBoneSet(); break;
|
||||
case SpineOnlyBoneSet: buildSpineOnlyBoneSet(); break;
|
||||
case LeftHandBoneSet: buildLeftHandBoneSet(); break;
|
||||
case RightHandBoneSet: buildRightHandBoneSet(); break;
|
||||
default:
|
||||
case EmptyBoneSet: buildEmptyBoneSet(); break;
|
||||
}
|
||||
|
@ -110,15 +112,6 @@ void AnimOverlay::buildLowerBodyBoneSet() {
|
|||
_boneSetVec[hipsJoint] = 0.0f;
|
||||
}
|
||||
|
||||
void AnimOverlay::buildRightArmBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
int rightShoulderJoint = _skeleton->nameToJointIndex("RightShoulder");
|
||||
for_each_child_joint(_skeleton, rightShoulderJoint, [&](int i) {
|
||||
_boneSetVec[i] = 1.0f;
|
||||
});
|
||||
}
|
||||
|
||||
void AnimOverlay::buildLeftArmBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
|
@ -128,6 +121,15 @@ void AnimOverlay::buildLeftArmBoneSet() {
|
|||
});
|
||||
}
|
||||
|
||||
void AnimOverlay::buildRightArmBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
int rightShoulderJoint = _skeleton->nameToJointIndex("RightShoulder");
|
||||
for_each_child_joint(_skeleton, rightShoulderJoint, [&](int i) {
|
||||
_boneSetVec[i] = 1.0f;
|
||||
});
|
||||
}
|
||||
|
||||
void AnimOverlay::buildAboveTheHeadBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
|
@ -168,13 +170,31 @@ void AnimOverlay::buildEmptyBoneSet() {
|
|||
}
|
||||
}
|
||||
|
||||
void AnimOverlay::buildLeftHandBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
int headJoint = _skeleton->nameToJointIndex("LeftHand");
|
||||
for_each_child_joint(_skeleton, headJoint, [&](int i) {
|
||||
_boneSetVec[i] = 1.0f;
|
||||
});
|
||||
}
|
||||
|
||||
void AnimOverlay::buildRightHandBoneSet() {
|
||||
assert(_skeleton);
|
||||
buildEmptyBoneSet();
|
||||
int headJoint = _skeleton->nameToJointIndex("RightHand");
|
||||
for_each_child_joint(_skeleton, headJoint, [&](int i) {
|
||||
_boneSetVec[i] = 1.0f;
|
||||
});
|
||||
}
|
||||
|
||||
// for AnimDebugDraw rendering
|
||||
const AnimPoseVec& AnimOverlay::getPosesInternal() const {
|
||||
return _poses;
|
||||
}
|
||||
|
||||
void AnimOverlay::setSkeletonInternal(AnimSkeleton::ConstPointer skeleton) {
|
||||
_skeleton = skeleton;
|
||||
AnimNode::setSkeletonInternal(skeleton);
|
||||
|
||||
// we have to re-build the bone set when the skeleton changes.
|
||||
buildBoneSet(_boneSet);
|
||||
|
|
|
@ -28,14 +28,16 @@ public:
|
|||
FullBodyBoneSet = 0,
|
||||
UpperBodyBoneSet,
|
||||
LowerBodyBoneSet,
|
||||
RightArmBoneSet,
|
||||
LeftArmBoneSet,
|
||||
RightArmBoneSet,
|
||||
AboveTheHeadBoneSet,
|
||||
BelowTheHeadBoneSet,
|
||||
HeadOnlyBoneSet,
|
||||
SpineOnlyBoneSet,
|
||||
EmptyBoneSet,
|
||||
NumBoneSets,
|
||||
LeftHandBoneSet,
|
||||
RightHandBoneSet,
|
||||
NumBoneSets
|
||||
};
|
||||
|
||||
AnimOverlay(const std::string& id, BoneSet boneSet, float alpha);
|
||||
|
@ -64,13 +66,15 @@ public:
|
|||
void buildFullBodyBoneSet();
|
||||
void buildUpperBodyBoneSet();
|
||||
void buildLowerBodyBoneSet();
|
||||
void buildRightArmBoneSet();
|
||||
void buildLeftArmBoneSet();
|
||||
void buildRightArmBoneSet();
|
||||
void buildAboveTheHeadBoneSet();
|
||||
void buildBelowTheHeadBoneSet();
|
||||
void buildHeadOnlyBoneSet();
|
||||
void buildSpineOnlyBoneSet();
|
||||
void buildEmptyBoneSet();
|
||||
void buildLeftHandBoneSet();
|
||||
void buildRightHandBoneSet();
|
||||
|
||||
// no copies
|
||||
AnimOverlay(const AnimOverlay&) = delete;
|
||||
|
|
|
@ -1048,6 +1048,62 @@ void Rig::updateEyeJoint(int index, const glm::vec3& modelTranslation, const glm
|
|||
}
|
||||
}
|
||||
|
||||
void Rig::updateFromHandParameters(const HandParameters& params) {
|
||||
|
||||
if (_enableAnimGraph && _animSkeleton) {
|
||||
|
||||
// AJT: TODO rotate these into the correct coordinate space
|
||||
/*
|
||||
if (params.isLeftEnabled) {
|
||||
auto rootTrans = _animSkeleton->getAbsoluteBindPose(_rootJointIndex).trans;
|
||||
_animVars.set("leftHandPosition", params.leftPosition + rootTrans);
|
||||
_animVars.set("leftHandRotation", params.leftOrientation);
|
||||
} else {
|
||||
_animVars.unset("leftHandPosition");
|
||||
_animVars.unset("leftHandRotation");
|
||||
}
|
||||
|
||||
if (params.isRightEnabled) {
|
||||
auto rootTrans = _animSkeleton->getAbsoluteBindPose(_rootJointIndex).trans;
|
||||
_animVars.set("rightHandPosition", params.rightPosition + rootTrans);
|
||||
_animVars.set("rightHandRotation", params.rightOrientation);
|
||||
} else {
|
||||
_animVars.unset("rightHandPosition");
|
||||
_animVars.unset("rightHandRotation");
|
||||
}
|
||||
*/
|
||||
|
||||
// AJT: REMOVE for grab/point debugging.
|
||||
_animVars.set("isLeftHandIdle", false);
|
||||
_animVars.set("isLeftHandPoint", false);
|
||||
_animVars.set("isLeftHandClose", false);
|
||||
if (params.leftTrigger > 0.3333f) {
|
||||
if (params.leftTrigger > 0.6666f) {
|
||||
_animVars.set("isLeftHandClose", true);
|
||||
} else {
|
||||
_animVars.set("isLeftHandPoint", true);
|
||||
}
|
||||
} else {
|
||||
_animVars.set("isLeftHandIdle", true);
|
||||
}
|
||||
|
||||
// AJT: REMOVE for grab/point debugging.
|
||||
_animVars.set("isRightHandIdle", false);
|
||||
_animVars.set("isRightHandPoint", false);
|
||||
_animVars.set("isRightHandClose", false);
|
||||
if (params.rightTrigger > 0.3333f) {
|
||||
if (params.rightTrigger > 0.6666f) {
|
||||
_animVars.set("isRightHandClose", true);
|
||||
} else {
|
||||
_animVars.set("isRightHandPoint", true);
|
||||
}
|
||||
} else {
|
||||
_animVars.set("isRightHandIdle", true);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void Rig::initAnimGraph(const QUrl& url, const FBXGeometry& fbxGeometry) {
|
||||
if (!_enableAnimGraph) {
|
||||
return;
|
||||
|
|
|
@ -76,6 +76,17 @@ public:
|
|||
void dump() const;
|
||||
};
|
||||
|
||||
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();
|
||||
float leftTrigger = 0.0f;
|
||||
float rightTrigger = 0.0f;
|
||||
};
|
||||
|
||||
virtual ~Rig() {}
|
||||
|
||||
RigPointer getRigPointer() { return shared_from_this(); }
|
||||
|
@ -172,6 +183,8 @@ public:
|
|||
void updateEyeJoints(int leftEyeIndex, int rightEyeIndex, const glm::vec3& modelTranslation, const glm::quat& modelRotation,
|
||||
const glm::quat& worldHeadOrientation, const glm::vec3& lookAtSpot, const glm::vec3& saccade = glm::vec3(0.0f));
|
||||
|
||||
void updateFromHandParameters(const HandParameters& params);
|
||||
|
||||
virtual void setHandPosition(int jointIndex, const glm::vec3& position, const glm::quat& rotation,
|
||||
float scale, float priority) = 0;
|
||||
|
||||
|
|
|
@ -52,190 +52,358 @@
|
|||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "mainStateMachine",
|
||||
"type": "stateMachine",
|
||||
"id": "rightHandOverlay",
|
||||
"type": "overlay",
|
||||
"data": {
|
||||
"currentState": "idle",
|
||||
"states": [
|
||||
{
|
||||
"id": "idle",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "walkFwd",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "walkBwd",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "strafeRight",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "strafeLeft",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "turnRight",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotTurning", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "turnLeft",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotTurning", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" }
|
||||
]
|
||||
}
|
||||
]
|
||||
"alpha": 1.0,
|
||||
"boneSet": "rightHand"
|
||||
},
|
||||
"children": [
|
||||
{
|
||||
"id": "idle",
|
||||
"type": "clip",
|
||||
"id": "rightHandStateMachine",
|
||||
"type": "stateMachine",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/idle.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 90.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
"currentState": "rightHandIdle",
|
||||
"states": [
|
||||
{
|
||||
"id": "rightHandIdle",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isRightHandPoint", "state": "rightHandPoint" },
|
||||
{ "var": "isRightHandClose", "state": "rightHandClose" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "rightHandPoint",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isRightHandIdle", "state": "rightHandIdle" },
|
||||
{ "var": "isRightHandClose", "state": "rightHandClose" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "rightHandClose",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isRightHandIdle", "state": "rightHandIdle" },
|
||||
{ "var": "isRightHandPoint", "state": "rightHandPoint" }
|
||||
]
|
||||
}
|
||||
]
|
||||
},
|
||||
"children": []
|
||||
"children": [
|
||||
{
|
||||
"id": "rightHandIdle",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/right_hand_anim.fbx",
|
||||
"startFrame": 30.0,
|
||||
"endFrame": 30.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "rightHandPoint",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/right_hand_anim.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 0.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "rightHandClose",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/right_hand_anim.fbx",
|
||||
"startFrame": 15.0,
|
||||
"endFrame": 15.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "walkFwd",
|
||||
"type": "clip",
|
||||
"id": "leftHandOverlay",
|
||||
"type": "overlay",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/walk_fwd.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 35.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true,
|
||||
"timeScaleVar": "walkTimeScale"
|
||||
"alpha": 1.0,
|
||||
"boneSet": "leftHand"
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "walkBwd",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/walk_bwd.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 37.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true,
|
||||
"timeScaleVar": "walkTimeScale"
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "turnLeft",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/turn_left.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 28.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "turnRight",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/turn_right.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 30.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "strafeLeft",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/strafe_left.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 31.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "strafeRight",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/strafe_right.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 31.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
"children": [
|
||||
{
|
||||
"id": "leftHandStateMachine",
|
||||
"type": "stateMachine",
|
||||
"data": {
|
||||
"currentState": "leftHandIdle",
|
||||
"states": [
|
||||
{
|
||||
"id": "leftHandIdle",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isLeftHandPoint", "state": "leftHandPoint" },
|
||||
{ "var": "isLeftHandClose", "state": "leftHandClose" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "leftHandPoint",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isLeftHandIdle", "state": "leftHandIdle" },
|
||||
{ "var": "isLeftHandClose", "state": "leftHandClose" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "leftHandClose",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isLeftHandIdle", "state": "leftHandIdle" },
|
||||
{ "var": "isLeftHandPoint", "state": "leftHandPoint" }
|
||||
]
|
||||
}
|
||||
]
|
||||
},
|
||||
"children": [
|
||||
{
|
||||
"id": "leftHandIdle",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/left_hand_anim.fbx",
|
||||
"startFrame": 30.0,
|
||||
"endFrame": 30.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "leftHandPoint",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/left_hand_anim.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 0.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "leftHandClose",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "http://hifi-public.s3.amazonaws.com/ozan/anim/squeeze_hands/left_hand_anim.fbx",
|
||||
"startFrame": 15.0,
|
||||
"endFrame": 15.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
}
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "mainStateMachine",
|
||||
"type": "stateMachine",
|
||||
"data": {
|
||||
"currentState": "idle",
|
||||
"states": [
|
||||
{
|
||||
"id": "idle",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "walkFwd",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "walkBwd",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "strafeRight",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "strafeLeft",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotMoving", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "turnRight",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotTurning", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningLeft", "state": "turnLeft" }
|
||||
]
|
||||
},
|
||||
{
|
||||
"id": "turnLeft",
|
||||
"interpTarget": 6,
|
||||
"interpDuration": 6,
|
||||
"transitions": [
|
||||
{ "var": "isNotTurning", "state": "idle" },
|
||||
{ "var": "isMovingForward", "state": "walkFwd" },
|
||||
{ "var": "isMovingBackward", "state": "walkBwd" },
|
||||
{ "var": "isMovingRight", "state": "strafeRight" },
|
||||
{ "var": "isMovingLeft", "state": "strafeLeft" },
|
||||
{ "var": "isTurningRight", "state": "turnRight" }
|
||||
]
|
||||
}
|
||||
]
|
||||
},
|
||||
"children": [
|
||||
{
|
||||
"id": "idle",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/idle.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 90.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "walkFwd",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/walk_fwd.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 35.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true,
|
||||
"timeScaleVar": "walkTimeScale"
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "walkBwd",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/walk_bwd.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 37.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true,
|
||||
"timeScaleVar": "walkTimeScale"
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "turnLeft",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/turn_left.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 28.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "turnRight",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/turn_right.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 30.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "strafeLeft",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/strafe_left.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 31.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
},
|
||||
{
|
||||
"id": "strafeRight",
|
||||
"type": "clip",
|
||||
"data": {
|
||||
"url": "https://hifi-public.s3.amazonaws.com/ozan/anim/standard_anims/strafe_right.fbx",
|
||||
"startFrame": 0.0,
|
||||
"endFrame": 31.0,
|
||||
"timeScale": 1.0,
|
||||
"loopFlag": true
|
||||
},
|
||||
"children": []
|
||||
}
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
||||
]
|
||||
}
|
||||
|
|
Loading…
Reference in a new issue