mirror of
https://github.com/overte-org/overte.git
synced 2025-08-09 06:18:52 +02:00
warning fixes
This commit is contained in:
parent
7b35e8c7fd
commit
0bcc3c023e
3 changed files with 8 additions and 8 deletions
|
@ -751,7 +751,7 @@ void AnimInverseKinematics::initConstraints() {
|
||||||
swungDirections.push_back(glm::vec3(cosf(theta), -0.5f, sinf(theta)));
|
swungDirections.push_back(glm::vec3(cosf(theta), -0.5f, sinf(theta)));
|
||||||
|
|
||||||
std::vector<float> minDots;
|
std::vector<float> minDots;
|
||||||
for (int i = 0; i < swungDirections.size(); i++) {
|
for (size_t i = 0; i < swungDirections.size(); i++) {
|
||||||
minDots.push_back(glm::dot(glm::normalize(swungDirections[i]), Vectors::UNIT_Y));
|
minDots.push_back(glm::dot(glm::normalize(swungDirections[i]), Vectors::UNIT_Y));
|
||||||
}
|
}
|
||||||
stConstraint->setSwingLimits(minDots);
|
stConstraint->setSwingLimits(minDots);
|
||||||
|
@ -961,11 +961,11 @@ void AnimInverseKinematics::initLimitCenterPoses() {
|
||||||
const float UPPER_ARM_THETA = PI / 3.0f; // 60 deg
|
const float UPPER_ARM_THETA = PI / 3.0f; // 60 deg
|
||||||
int leftArmIndex = _skeleton->nameToJointIndex("LeftArm");
|
int leftArmIndex = _skeleton->nameToJointIndex("LeftArm");
|
||||||
const glm::quat armRot = glm::angleAxis(UPPER_ARM_THETA, Vectors::UNIT_X);
|
const glm::quat armRot = glm::angleAxis(UPPER_ARM_THETA, Vectors::UNIT_X);
|
||||||
if (leftArmIndex >= 0 && leftArmIndex < _limitCenterPoses.size()) {
|
if (leftArmIndex >= 0 && leftArmIndex < (int)_limitCenterPoses.size()) {
|
||||||
_limitCenterPoses[leftArmIndex].rot() = _limitCenterPoses[leftArmIndex].rot() * armRot;
|
_limitCenterPoses[leftArmIndex].rot() = _limitCenterPoses[leftArmIndex].rot() * armRot;
|
||||||
}
|
}
|
||||||
int rightArmIndex = _skeleton->nameToJointIndex("RightArm");
|
int rightArmIndex = _skeleton->nameToJointIndex("RightArm");
|
||||||
if (rightArmIndex >= 0 && rightArmIndex < _limitCenterPoses.size()) {
|
if (rightArmIndex >= 0 && rightArmIndex < (int)_limitCenterPoses.size()) {
|
||||||
_limitCenterPoses[rightArmIndex].rot() = _limitCenterPoses[rightArmIndex].rot() * armRot;
|
_limitCenterPoses[rightArmIndex].rot() = _limitCenterPoses[rightArmIndex].rot() * armRot;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1027,7 +1027,7 @@ void AnimInverseKinematics::debugDrawConstraints(const AnimContext& context) con
|
||||||
AnimPoseVec poses = _skeleton->getRelativeDefaultPoses();
|
AnimPoseVec poses = _skeleton->getRelativeDefaultPoses();
|
||||||
|
|
||||||
// copy reference rotations into the relative poses
|
// copy reference rotations into the relative poses
|
||||||
for (int i = 0; i < poses.size(); i++) {
|
for (int i = 0; i < (int)poses.size(); i++) {
|
||||||
const RotationConstraint* constraint = getConstraint(i);
|
const RotationConstraint* constraint = getConstraint(i);
|
||||||
if (constraint) {
|
if (constraint) {
|
||||||
poses[i].rot() = constraint->getReferenceRotation();
|
poses[i].rot() = constraint->getReferenceRotation();
|
||||||
|
@ -1040,7 +1040,7 @@ void AnimInverseKinematics::debugDrawConstraints(const AnimContext& context) con
|
||||||
mat4 geomToWorldMatrix = context.getRigToWorldMatrix() * context.getGeometryToRigMatrix();
|
mat4 geomToWorldMatrix = context.getRigToWorldMatrix() * context.getGeometryToRigMatrix();
|
||||||
|
|
||||||
// draw each pose and constraint
|
// draw each pose and constraint
|
||||||
for (int i = 0; i < poses.size(); i++) {
|
for (int i = 0; i < (int)poses.size(); i++) {
|
||||||
// transform local axes into world space.
|
// transform local axes into world space.
|
||||||
auto pose = poses[i];
|
auto pose = poses[i];
|
||||||
glm::vec3 xAxis = transformVectorFast(geomToWorldMatrix, pose.rot() * Vectors::UNIT_X);
|
glm::vec3 xAxis = transformVectorFast(geomToWorldMatrix, pose.rot() * Vectors::UNIT_X);
|
||||||
|
|
|
@ -112,7 +112,7 @@ public:
|
||||||
void clearJointStates();
|
void clearJointStates();
|
||||||
void clearJointAnimationPriority(int index);
|
void clearJointAnimationPriority(int index);
|
||||||
|
|
||||||
std::shared_ptr<AnimInverseKinematics> Rig::getAnimInverseKinematicsNode() const;
|
std::shared_ptr<AnimInverseKinematics> getAnimInverseKinematicsNode() const;
|
||||||
|
|
||||||
void clearIKJointLimitHistory();
|
void clearIKJointLimitHistory();
|
||||||
void setMaxHipsOffsetLength(float maxLength);
|
void setMaxHipsOffsetLength(float maxLength);
|
||||||
|
|
|
@ -101,8 +101,8 @@ public:
|
||||||
|
|
||||||
virtual glm::quat computeCenterRotation() const override;
|
virtual glm::quat computeCenterRotation() const override;
|
||||||
|
|
||||||
const float getMinTwist() const { return _minTwist; }
|
float getMinTwist() const { return _minTwist; }
|
||||||
const float getMaxTwist() const { return _maxTwist; }
|
float getMaxTwist() const { return _maxTwist; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float handleTwistBoundaryConditions(float twistAngle) const;
|
float handleTwistBoundaryConditions(float twistAngle) const;
|
||||||
|
|
Loading…
Reference in a new issue