Skip to content

Remove Affine3 from JointState #49

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions momentum/character/blend_shape_skinning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,7 @@ void skinWithBlendShapes(
// first create a list of transformations from bindpose to final output pose
std::vector<Eigen::Matrix4<T>> transformations(state.jointState.size());
for (size_t i = 0; i < state.jointState.size(); i++) {
transformations[i] =
(state.jointState[i].transformation * inverseBindPose[i].cast<T>()).matrix();
transformations[i] = (state.jointState[i].transform * inverseBindPose[i].cast<T>()).matrix();
}

MT_CHECK(
Expand Down
29 changes: 15 additions & 14 deletions momentum/character/character.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,11 +241,12 @@ CharacterT<T> CharacterT<T>::simplifySkeleton(const std::vector<bool>& enabledJo
currentParent = lastJoint[sIndex];
}
// calculate the new offset of the joint in the new parent space
if (sIndex != kInvalidIndex)
offset = referenceState.jointState[sIndex].transformation.inverse() *
referenceState.jointState[aIndex].translation;
else
offset = referenceState.jointState[aIndex].translation;
if (sIndex != kInvalidIndex) {
offset = referenceState.jointState[sIndex].transform.inverse() *
referenceState.jointState[aIndex].translation();
} else {
offset = referenceState.jointState[aIndex].translation();
}
}

// is joint enabled?
Expand Down Expand Up @@ -328,8 +329,8 @@ CharacterT<T> CharacterT<T>::simplifySkeleton(const std::vector<bool>& enabledJo
for (auto&& c : *result.collision) {
const auto oldParent = c.parent;
c.parent = result.jointMap[c.parent];
c.transformation = targetBindState.jointState[c.parent].transformation.inverse() *
sourceBindState.jointState[oldParent].transformation * c.transformation;
c.transformation = targetBindState.jointState[c.parent].transform.inverse() *
sourceBindState.jointState[oldParent].transform * c.transformation;
}
}

Expand Down Expand Up @@ -461,15 +462,15 @@ ParameterLimits CharacterT<T>::remapParameterLimits(
data.parent = targetParent;

const auto targetTransformationInverse =
targetBindState.jointState[targetParent].transformation.inverse();
const auto sourceTransformation = sourceBindState.jointState[sourceParent].transformation;
targetBindState.jointState[targetParent].transform.inverse();
const auto sourceTransformation = sourceBindState.jointState[sourceParent].transform;
data.offset = targetTransformationInverse * sourceTransformation * data.offset;

const auto sourceEllipsoidParent = data.ellipsoidParent;
data.ellipsoidParent = jointMap[data.ellipsoidParent];
const auto targetEllipsoidInverse =
targetBindState.jointState[data.ellipsoidParent].transformation.inverse();
const auto sourceEllipsoid = sourceBindState.jointState[sourceEllipsoidParent].transformation;
targetBindState.jointState[data.ellipsoidParent].transform.inverse();
const auto sourceEllipsoid = sourceBindState.jointState[sourceEllipsoidParent].transform;
data.ellipsoid = targetEllipsoidInverse * sourceEllipsoid * data.ellipsoid;
data.ellipsoidInv = data.ellipsoid.inverse();
}
Expand Down Expand Up @@ -506,8 +507,8 @@ LocatorList CharacterT<T>::remapLocators(
result.emplace_back(sourceLocator);
auto& loc = result.back();
loc.parent = jointMap[loc.parent];
loc.offset = targetBindState.jointState[loc.parent].transformation.inverse() *
sourceBindState.jointState[sourceLocator.parent].transformation * sourceLocator.offset;
loc.offset = targetBindState.jointState[loc.parent].transform.inverse() *
sourceBindState.jointState[sourceLocator.parent].transform * sourceLocator.offset;
}

return result;
Expand Down Expand Up @@ -542,7 +543,7 @@ void CharacterT<T>::initInverseBindPose() {
inverseBindPose.clear();
inverseBindPose.reserve(bindState.jointState.size());
for (const auto& t : bindState.jointState)
inverseBindPose.push_back(t.transformation.inverse());
inverseBindPose.push_back(t.transform.toAffine3().inverse());
}

template <typename T>
Expand Down
4 changes: 2 additions & 2 deletions momentum/character/collision_geometry_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ void CollisionGeometryStateT<T>::update(
for (size_t i = 0; i < numElements; ++i) {
const auto& tc = collisionGeometry[i];
const auto& js = skeletonState.jointState[tc.parent];
const Affine3<T> transform = js.transformation * tc.transformation.cast<T>();
const Affine3<T> transform = js.transform * tc.transformation.cast<T>();
origin[i] = transform.translation();
direction[i].noalias() = transform.linear().col(0) * tc.length;
radius[i].noalias() = tc.radius.cast<T>() * js.scale;
radius[i].noalias() = tc.radius.cast<T>() * js.scale();
delta[i] = radius[i][1] - radius[i][0];
}
}
Expand Down
20 changes: 1 addition & 19 deletions momentum/character/joint_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ void JointStateT<T>::set(
// calculate state based on parameters and parent transform
if (computeDeriv) {
if (parentState != nullptr) {
translationAxis = parentState->transformation.linear();
translationAxis = parentState->transform.toLinear(); // TODO: linear() or rotation()
} else {
translationAxis.setIdentity();
}
Expand All @@ -62,15 +62,6 @@ void JointStateT<T>::set(

// set global transformation
transform = parent * localTransform;

// TODO: Remove
localTranslation = localTransform.translation;
localRotation = localTransform.rotation;
localScale = localTransform.scale;
translation = transform.translation;
rotation = transform.rotation;
scale = transform.scale;
transformation = transform.toAffine3();
}

template <typename T>
Expand All @@ -95,15 +86,6 @@ Eigen::Vector3<T> JointStateT<T>::getScaleDerivative(const Eigen::Vector3<T>& re
template <typename T>
template <typename T2>
void JointStateT<T>::set(const JointStateT<T2>& rhs) {
// TODO: Remove
localRotation = rhs.localRotation.template cast<T>();
localTranslation = rhs.localTranslation.template cast<T>();
localScale = (T)rhs.localScale;
rotation = rhs.rotation.template cast<T>();
translation = rhs.translation.template cast<T>();
scale = (T)rhs.scale;
transformation = rhs.transformation.template cast<T>();

localTransform = rhs.localTransform.template cast<T>();
transform = rhs.transform.template cast<T>();

Expand Down
160 changes: 113 additions & 47 deletions momentum/character/joint_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,25 +23,6 @@ template <typename T>
struct JointStateT {
using Affine3 = Eigen::Transform<T, 3, Eigen::Affine>;

// local joint transformation as defined by parameters
/// Local rotation matrix
Eigen::Quaternion<T> localRotation; // TODO: Remove
/// Local translation offset
Eigen::Vector3<T> localTranslation; // TODO: Remove
/// Local scaling (affects descendants)
T localScale; // TODO: Remove

// joint transformation from local to global space
/// Rotation matrix from local to global space
Eigen::Quaternion<T> rotation; // TODO: Remove
/// Translation offset from local to global space
Eigen::Vector3<T> translation; // TODO: Remove
/// Scaling from local to global space
T scale; // TODO: Remove

/// Local to global complete matrix
Affine3 transformation; // TODO: Remove

/// Relative transformation from the parent joint to this joint, which is defined by the
/// joint parameters
TransformT<T> localTransform;
Expand All @@ -58,34 +39,6 @@ struct JointStateT {
/// Indicate whether translationAxis and rotationAxis are up-to-date with other transformations
bool derivDirty = true;

// TODO: Remove
explicit JointStateT(
const Eigen::Quaternion<T>& localRotation = Eigen::Quaternion<T>(),
const Eigen::Vector3<T>& localTranslation = Eigen::Vector3<T>(),
const T& localScale = T(),
const Eigen::Quaternion<T>& rotation = Eigen::Quaternion<T>(),
const Eigen::Vector3<T>& translation = Eigen::Vector3<T>(),
const T& scale = T(),
const Affine3& transformation = Affine3(),
const Eigen::Matrix3<T>& translationAxis = Eigen::Matrix3<T>(),
const Eigen::Matrix3<T>& rotationAxis = Eigen::Matrix3<T>())
: localRotation(localRotation),
localTranslation(localTranslation),
localScale(localScale),
rotation(rotation),
translation(translation),
scale(scale),
transformation(transformation),
translationAxis(translationAxis),
rotationAxis(rotationAxis) {
localTransform.rotation = localRotation;
localTransform.translation = localTranslation;
localTransform.scale = localScale;
transform.rotation = rotation;
transform.translation = translation;
transform.scale = scale;
}

/// Recursively update all the transformations from the root to leaves
void set(
const JointT<T>& joint,
Expand All @@ -110,6 +63,119 @@ struct JointStateT {
template <typename T2>
void set(const JointStateT<T2>& rhs);

/// Local rotation matrix
[[nodiscard]] const Quaternion<T>& localRotation() const {
return localTransform.rotation;
}

Quaternion<T>& localRotation() {
return localTransform.rotation;
}

/// Local translation offset
[[nodiscard]] const Vector3<T>& localTranslation() const {
return localTransform.translation;
}

Vector3<T>& localTranslation() {
return localTransform.translation;
}

/// Local scaling (affects descendants)
[[nodiscard]] const T& localScale() const {
return localTransform.scale;
}

T& localScale() {
return localTransform.scale;
}

/// Rotation matrix from local to global space
[[nodiscard]] const Quaternion<T>& rotation() const {
return transform.rotation;
}

Quaternion<T>& rotation() {
return transform.rotation;
}

/// Translation offset from local to global space
[[nodiscard]] const Vector3<T>& translation() const {
return transform.translation;
}

Vector3<T>& translation() {
return transform.translation;
}

/// Return the X component of the global transform
[[nodiscard]] const T& x() const {
return transform.translation.x();
}

T& x() {
return transform.translation.x();
}

/// Return the Y component of the global transform
[[nodiscard]] const T& y() const {
return transform.translation.y();
}

T& y() {
return transform.translation.y();
}

/// Return the Z component of the global transform
[[nodiscard]] const T& z() const {
return transform.translation.z();
}

T& z() {
return transform.translation.z();
}

[[nodiscard]] const T& quatW() const {
return transform.rotation.w();
}

T& quatW() {
return transform.rotation.w();
}

[[nodiscard]] const T& quatX() const {
return transform.rotation.x();
}

T& quatX() {
return transform.rotation.x();
}

[[nodiscard]] const T& quatY() const {
return transform.rotation.y();
}

T& quatY() {
return transform.rotation.y();
}

[[nodiscard]] const T& quatZ() const {
return transform.rotation.z();
}

T& quatZ() {
return transform.rotation.z();
}

/// Scaling from local to global space
[[nodiscard]] const T& scale() const {
return transform.scale;
}

T& scale() {
return transform.scale;
}

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};

Expand Down
8 changes: 4 additions & 4 deletions momentum/character/linear_skinning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ std::vector<Vector3<T>> applySSD(
// first create a list of transformations from bindpose to final output pose
std::vector<Matrix4<T>> transformations(state.jointState.size());
for (size_t i = 0; i < state.jointState.size(); i++) {
transformations[i] = (state.jointState[i].transformation * inverseBindPose[i]).matrix();
transformations[i] = (state.jointState[i].transform * inverseBindPose[i]).matrix();
}

// go over all vertices and perform transformation
Expand Down Expand Up @@ -137,7 +137,7 @@ void applySSD(
// first create a list of transformations from bindpose to final output pose
std::vector<Eigen::Matrix4<T>> transformations(inverseBindPose.size());
for (size_t i = 0; i < inverseBindPose.size(); i++) {
transformations[i].noalias() = (jointState[i].transformation * inverseBindPose[i]).matrix();
transformations[i].noalias() = (jointState[i].transform * inverseBindPose[i]).matrix();
}

// go over all vertices and perform transformation
Expand Down Expand Up @@ -212,7 +212,7 @@ Affine3f getInverseSSDTransformation(

auto jointIndex = skin.index(index, j);
const auto transformation =
state.jointState[jointIndex].transformation * inverseBindPose[jointIndex];
state.jointState[jointIndex].transform * inverseBindPose[jointIndex];

// add up transforms
transform.matrix().noalias() += transformation.matrix() * weight;
Expand Down Expand Up @@ -259,7 +259,7 @@ std::vector<Vector3f> applyInverseSSD(
// first create a list of transformations from bindpose to final output pose
TransformationList transformations(state.jointState.size());
for (size_t i = 0; i < state.jointState.size(); i++) {
transformations[i] = state.jointState[i].transformation * inverseBindPose[i];
transformations[i] = state.jointState[i].transform * inverseBindPose[i];
}

// go over all vertices and perform transformation
Expand Down
2 changes: 1 addition & 1 deletion momentum/character/locator_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ void LocatorState::update(
const size_t& parentId = locator.parent;

// transform each locator by its parents transformation and store it in the locator state
position[locatorID] = jointState[parentId].transformation * locator.offset;
position[locatorID] = jointState[parentId].transform * locator.offset;
}
}

Expand Down
4 changes: 2 additions & 2 deletions momentum/character/pose_shape.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,12 @@ std::vector<Vector3f> PoseShape::compute(const SkeletonState& state) const {
VectorXf coefficients(shapeVectors.cols());

// calculate base transform
const Quaternionf base = baseRot * state.jointState[baseJoint].rotation.inverse();
const Quaternionf base = baseRot * state.jointState[baseJoint].rotation().inverse();

// set up pose shape coefficients
for (size_t i = 0; i < jointMap.size(); i++) {
const auto& jid = jointMap[i];
coefficients.segment<4>(i * 4) = (base * state.jointState[jid].rotation).coeffs();
coefficients.segment<4>(i * 4) = (base * state.jointState[jid].rotation()).coeffs();
}

// use the coefficients to calculate the new base shape
Expand Down
6 changes: 3 additions & 3 deletions momentum/character/skeleton_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,11 +150,11 @@ StateSimilarity SkeletonStateT<T>::compare(
// calculate position error and orientation error in global coordinates per joint
for (size_t i = 0; i < state1.jointState.size(); i++) {
result.positionError[i] =
(state1.jointState[i].translation - state2.jointState[i].translation).norm();
(state1.jointState[i].translation() - state2.jointState[i].translation()).norm();
const double dot = std::min(
std::max(
state1.jointState[i].rotation.normalized().dot(
state2.jointState[i].rotation.normalized()),
state1.jointState[i].rotation().normalized().dot(
state2.jointState[i].rotation().normalized()),
T(-1.0)),
T(1.0));
const double sgn = dot < 0.0 ? -1.0 : 1.0;
Expand Down
Loading