Add new pose setting: yTranslationScale

Normally, when pose been generated, foot is always been pulling to the ground by a y-translation. This setting could be used to scale the y-translation. It's usefull for birds fly kind of motion.
master
Jeremy Hu 2019-06-19 22:27:38 +09:30
parent 3e29528ee0
commit 516df9a1b7
11 changed files with 105 additions and 59 deletions

View File

@ -20,62 +20,31 @@ void AnimalPoser::resolveTransform()
resolveChainRotation(chain.second);
}
//int firstSpineBoneIndex = findBoneIndex(Rigger::firstSpineBoneName);
//if (-1 == firstSpineBoneIndex) {
// qDebug() << "Find first spine bone failed:" << Rigger::firstSpineBoneName;
// return;
//}
//const auto &firstSpineBone = bones()[firstSpineBoneIndex];
float mostBottomYBeforeTransform = std::numeric_limits<float>::max();
for (const auto &bone: bones()) {
if (bone.tailPosition.y() < mostBottomYBeforeTransform)
mostBottomYBeforeTransform = bone.tailPosition.y();
}
//float legHeightBeforeTransform = std::abs(mostBottomYBeforeTransform - firstSpineBone.headPosition.y());
auto transformedJointNodeTree = m_jointNodeTree;
transformedJointNodeTree.recalculateTransformMatrices();
float mostBottomYAfterTransform = std::numeric_limits<float>::max();
//QVector3D firstSpineBonePositionAfterTransform = firstSpineBone.headPosition;
for (int i = 0; i < (int)transformedJointNodeTree.nodes().size(); ++i) {
const auto &bone = bones()[i];
const auto &jointNode = transformedJointNodeTree.nodes()[i];
QVector3D newPosition = jointNode.transformMatrix * bone.tailPosition;
//if (0 == i) {
// Root bone's tail position is the first spine bone's head position
// firstSpineBonePositionAfterTransform = newPosition;
//}
if (newPosition.y() < mostBottomYAfterTransform)
mostBottomYAfterTransform = newPosition.y();
}
//float legHeightAfterTransform = std::abs(mostBottomYAfterTransform - firstSpineBonePositionAfterTransform.y());
//float translateY = legHeightAfterTransform - legHeightBeforeTransform;
float translateY = mostBottomYBeforeTransform - mostBottomYAfterTransform;
//qDebug() << "Leg height changed, translateY:" << translateY << "legHeightBeforeTransform:" << legHeightBeforeTransform << "legHeightAfterTransform:" << legHeightAfterTransform << "firstSpineBonePositionAfterTransform:" << firstSpineBonePositionAfterTransform << "firstSpineBone.headPosition:" << firstSpineBone.headPosition;
/*
const auto &findRootParameters = parameters().find(Rigger::rootBoneName);
if (findRootParameters != parameters().end()) {
auto findHeightAboveGroundLevel = findRootParameters->second.find("heightAboveGroundLevel");
if (findHeightAboveGroundLevel != findRootParameters->second.end()) {
float heightAboveGroundLevel = findHeightAboveGroundLevel->second.toFloat();
float myHeightAboveGroundLevel = heightAboveGroundLevel * legHeightAfterTransform;
translateY += myHeightAboveGroundLevel;
//qDebug() << "heightAboveGroundLevel:" << heightAboveGroundLevel << "myHeightAboveGroundLevel:" << myHeightAboveGroundLevel << "legHeightBeforeTransform:" << legHeightBeforeTransform << "applied translateY:" << translateY;
}
}
*/
if (!qFuzzyIsNull(translateY)) {
int rootBoneIndex = findBoneIndex(Rigger::rootBoneName);
if (-1 == rootBoneIndex) {
qDebug() << "Find root bone failed:" << Rigger::rootBoneName;
return;
}
m_jointNodeTree.addTranslation(rootBoneIndex, QVector3D(0, translateY, 0));
m_jointNodeTree.addTranslation(rootBoneIndex, QVector3D(0, translateY * m_yTranslationScale, 0));
}
}
@ -186,7 +155,7 @@ void AnimalPoser::resolveChainRotation(const std::vector<QString> &limbBoneNames
QVector3D targetMiddleBoneStartPosition;
{
//qDebug() << beginBoneName << "Angle:" << angleBetweenDistanceAndMiddleBones;
qDebug() << beginBoneName << "Angle:" << angleBetweenDistanceAndMiddleBones << "Distance:" << targetDistanceBetweenBeginAndEndBones;
auto rotation = QQuaternion::fromAxisAndAngle(matchRotatePlaneNormal, angleBetweenDistanceAndMiddleBones);
targetMiddleBoneStartPosition = targetEndBoneStartPosition + rotation.rotatedVector(-matchDirectionBetweenBeginAndEndPones).normalized() * targetMiddleBoneLength;
}

View File

@ -356,7 +356,7 @@ QUuid Document::createNode(QUuid nodeId, float x, float y, float z, float radius
return node.id;
}
void Document::addPose(QUuid poseId, QString name, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames, QUuid turnaroundImageId)
void Document::addPose(QUuid poseId, QString name, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames, QUuid turnaroundImageId, float yTranslationScale)
{
QUuid newPoseId = poseId;
auto &pose = poseMap[newPoseId];
@ -365,6 +365,7 @@ void Document::addPose(QUuid poseId, QString name, std::vector<std::pair<std::ma
pose.name = name;
pose.frames = frames;
pose.turnaroundImageId = turnaroundImageId;
pose.yTranslationScale = yTranslationScale;
pose.dirty = true;
poseIdList.push_back(newPoseId);
@ -481,6 +482,19 @@ void Document::setPoseTurnaroundImageId(QUuid poseId, QUuid imageId)
emit optionsChanged();
}
void Document::setPoseYtranslationScale(QUuid poseId, float scale)
{
auto findPoseResult = poseMap.find(poseId);
if (findPoseResult == poseMap.end()) {
qDebug() << "Find pose failed:" << poseId;
return;
}
findPoseResult->second.yTranslationScale = scale;
findPoseResult->second.dirty = true;
emit poseYtranslationScaleChanged(poseId);
emit optionsChanged();
}
void Document::renamePose(QUuid poseId, QString name)
{
auto findPoseResult = poseMap.find(poseId);
@ -1061,6 +1075,8 @@ void Document::toSnapshot(Snapshot *snapshot, const std::set<QUuid> &limitNodeId
pose["name"] = poseIt.second.name;
if (!poseIt.second.turnaroundImageId.isNull())
pose["canvasImageId"] = poseIt.second.turnaroundImageId.toString();
if (poseIt.second.yTranslationScaleAdjusted())
pose["yTranslationScale"] = QString::number(poseIt.second.yTranslationScale);
snapshot->poses.push_back(std::make_pair(pose, poseIt.second.frames));
}
}
@ -1341,6 +1357,9 @@ void Document::addFromSnapshot(const Snapshot &snapshot, bool fromPaste)
auto findCanvasImageId = poseAttributes.find("canvasImageId");
if (findCanvasImageId != poseAttributes.end())
newPose.turnaroundImageId = QUuid(findCanvasImageId->second);
auto findYtranslationScale = poseAttributes.find("yTranslationScale");
if (findYtranslationScale != poseAttributes.end())
newPose.yTranslationScale = findYtranslationScale->second.toFloat();
newPose.frames = poseIt.second;
oldNewIdMap[QUuid(valueOfKeyInMapOrEmpty(poseAttributes, "id"))] = newPoseId;
poseIdList.push_back(newPoseId);
@ -2875,7 +2894,7 @@ void Document::generateMotions()
m_motionsGenerator = new MotionsGenerator(rigType, rigBones, rigWeights, currentRiggedOutcome());
bool hasDirtyMotion = false;
for (const auto &pose: poseMap) {
m_motionsGenerator->addPoseToLibrary(pose.first, pose.second.frames);
m_motionsGenerator->addPoseToLibrary(pose.first, pose.second.frames, pose.second.yTranslationScale);
}
for (auto &motion: motionMap) {
if (motion.second.dirty) {

View File

@ -198,6 +198,7 @@ public:
QString name;
bool dirty = true;
QUuid turnaroundImageId;
float yTranslationScale = 1.0;
std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames; // pair<attributes, parameters>
void updatePreviewMesh(MeshLoader *previewMesh)
{
@ -210,6 +211,10 @@ public:
return nullptr;
return new MeshLoader(*m_previewMesh);
}
bool yTranslationScaleAdjusted() const
{
return fabs(yTranslationScale - 1.0) >= 0.01;
}
private:
Q_DISABLE_COPY(Pose);
MeshLoader *m_previewMesh = nullptr;
@ -434,6 +439,7 @@ signals:
void poseNameChanged(QUuid poseId);
void poseFramesChanged(QUuid poseId);
void poseTurnaroundImageIdChanged(QUuid poseId);
void poseYtranslationScaleChanged(QUuid poseId);
void posePreviewChanged(QUuid poseId);
void motionAdded(QUuid motionId);
void motionRemoved(QUuid motionId);
@ -612,10 +618,12 @@ public slots:
void enableWeld(bool enabled);
void setRigType(RigType toRigType);
void addPose(QUuid poseId, QString name, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames,
QUuid turnaroundImageId);
QUuid turnaroundImageId,
float yTranslationScale);
void removePose(QUuid poseId);
void setPoseFrames(QUuid poseId, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames);
void setPoseTurnaroundImageId(QUuid poseId, QUuid imageId);
void setPoseYtranslationScale(QUuid poseId, float scale);
void renamePose(QUuid poseId, QString name);
void addMotion(QUuid motionId, QString name, std::vector<MotionClip> clips);
void removeMotion(QUuid motionId);

View File

@ -251,7 +251,7 @@ void MotionEditWidget::generatePreviews()
m_previewsGenerator = new MotionsGenerator(m_document->rigType, rigBones, rigWeights,
m_document->currentRiggedOutcome());
for (const auto &pose: m_document->poseMap)
m_previewsGenerator->addPoseToLibrary(pose.first, pose.second.frames);
m_previewsGenerator->addPoseToLibrary(pose.first, pose.second.frames, pose.second.yTranslationScale);
for (const auto &motion: m_document->motionMap)
m_previewsGenerator->addMotionToLibrary(motion.first, motion.second.clips);
m_previewsGenerator->addMotionToLibrary(QUuid(), m_timelineWidget->clips());

View File

@ -27,9 +27,10 @@ MotionsGenerator::~MotionsGenerator()
delete m_poser;
}
void MotionsGenerator::addPoseToLibrary(const QUuid &poseId, const std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> &frames)
void MotionsGenerator::addPoseToLibrary(const QUuid &poseId, const std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> &frames, float yTranslationScale)
{
m_poses[poseId] = frames;
m_posesYtranslationScales[poseId] = yTranslationScale;
}
void MotionsGenerator::addMotionToLibrary(const QUuid &motionId, const std::vector<MotionClip> &clips)
@ -231,6 +232,7 @@ const JointNodeTree &MotionsGenerator::poseJointNodeTree(const QUuid &poseId, in
return findResult->second;
const auto &frames = m_poses[poseId];
const auto &posesYtranslationScale = m_posesYtranslationScales[poseId];
m_poser->reset();
if (frame < (int)frames.size()) {
@ -240,6 +242,7 @@ const JointNodeTree &MotionsGenerator::poseJointNodeTree(const QUuid &poseId, in
std::map<QString, std::map<QString, QString>> translatedParameters;
postDocument.toParameters(translatedParameters);
m_poser->parameters() = translatedParameters;
m_poser->setYtranslationScale(posesYtranslationScale);
}
m_poser->commit();
auto insertResult = m_poseJointNodeTreeMap.insert({{poseId, frame}, m_poser->resultJointNodeTree()});

View File

@ -19,7 +19,7 @@ public:
const std::map<int, RiggerVertexWeights> *rigWeights,
const Outcome &outcome);
~MotionsGenerator();
void addPoseToLibrary(const QUuid &poseId, const std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> &frames);
void addPoseToLibrary(const QUuid &poseId, const std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> &frames, float yTranslationScale);
void addMotionToLibrary(const QUuid &motionId, const std::vector<MotionClip> &clips);
void addRequirement(const QUuid &motionId);
std::vector<std::pair<float, MeshLoader *>> takeResultPreviewMeshs(const QUuid &motionId);
@ -50,6 +50,7 @@ private:
std::map<int, RiggerVertexWeights> m_rigWeights;
Outcome m_outcome;
std::map<QUuid, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>>> m_poses;
std::map<QUuid, float> m_posesYtranslationScales;
std::map<QUuid, std::vector<MotionClip>> m_motions;
std::set<QUuid> m_requiredMotionIds;
std::set<QUuid> m_generatedMotionIds;

View File

@ -194,6 +194,11 @@ PoseEditWidget::PoseEditWidget(const Document *document, QWidget *parent) :
connect(saveButton, &QPushButton::clicked, this, &PoseEditWidget::save);
saveButton->setDefault(true);
QPushButton *setPoseSettingButton = new QPushButton(Theme::awesome()->icon(fa::gear), tr(""));
connect(setPoseSettingButton, &QPushButton::clicked, this, [=]() {
showPoseSettingPopup(mapFromGlobal(QCursor::pos()));
});
QPushButton *changeReferenceSheet = new QPushButton(tr("Change Reference Sheet..."));
connect(changeReferenceSheet, &QPushButton::clicked, this, &PoseEditWidget::changeTurnaround);
connect(m_poseDocument, &PoseDocument::turnaroundChanged,
@ -261,6 +266,7 @@ PoseEditWidget::PoseEditWidget(const Document *document, QWidget *parent) :
baseInfoLayout->addWidget(new QLabel(tr("Duration")));
baseInfoLayout->addWidget(m_durationEdit);
baseInfoLayout->addStretch();
baseInfoLayout->addWidget(setPoseSettingButton);
baseInfoLayout->addWidget(changeReferenceSheet);
baseInfoLayout->addWidget(saveButton);
@ -280,6 +286,7 @@ PoseEditWidget::PoseEditWidget(const Document *document, QWidget *parent) :
connect(this, &PoseEditWidget::renamePose, m_document, &Document::renamePose);
connect(this, &PoseEditWidget::setPoseFrames, m_document, &Document::setPoseFrames);
connect(this, &PoseEditWidget::setPoseTurnaroundImageId, m_document, &Document::setPoseTurnaroundImageId);
connect(this, &PoseEditWidget::setPoseYtranslationScale, m_document, &Document::setPoseYtranslationScale);
updatePoseDocument();
updateTitle();
@ -308,6 +315,43 @@ void PoseEditWidget::updateSideButtonState(QPushButton *button, bool visible)
button->setStyleSheet("QPushButton {color: #252525}");
}
void PoseEditWidget::showPoseSettingPopup(const QPoint &pos)
{
QMenu popupMenu;
QWidget *popup = new QWidget;
FloatNumberWidget *yTranslationScaleWidget = new FloatNumberWidget;
yTranslationScaleWidget->setItemName(tr("Height Adjustment Scale"));
yTranslationScaleWidget->setRange(0, 1);
yTranslationScaleWidget->setValue(m_yTranslationScale);
connect(yTranslationScaleWidget, &FloatNumberWidget::valueChanged, [&](float value) {
m_yTranslationScale = value;
setUnsaveState();
});
QPushButton *yTranslationScaleEraser = new QPushButton(QChar(fa::eraser));
Theme::initAwesomeToolButton(yTranslationScaleEraser);
connect(yTranslationScaleEraser, &QPushButton::clicked, [=]() {
yTranslationScaleWidget->setValue(1.0);
});
QHBoxLayout *yTranslationScaleLayout = new QHBoxLayout;
yTranslationScaleLayout->addWidget(yTranslationScaleEraser);
yTranslationScaleLayout->addWidget(yTranslationScaleWidget);
popup->setLayout(yTranslationScaleLayout);
QWidgetAction *action = new QWidgetAction(this);
action->setDefaultWidget(popup);
popupMenu.addAction(action);
popupMenu.exec(mapToGlobal(pos));
}
void PoseEditWidget::showFramesSettingPopup(const QPoint &pos)
{
QMenu popupMenu;
@ -315,13 +359,13 @@ void PoseEditWidget::showFramesSettingPopup(const QPoint &pos)
QWidget *popup = new QWidget;
QSpinBox *framesEdit = new QSpinBox();
framesEdit->setMaximum(60);
framesEdit->setMaximum(m_frames.size());
framesEdit->setMinimum(1);
framesEdit->setSingleStep(1);
framesEdit->setValue(m_frames.size());
connect(framesEdit, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged), this, [=](int value) {
setFrameCount(value);
setCurrentFrame(value);
});
QFormLayout *formLayout = new QFormLayout;
@ -361,21 +405,6 @@ void PoseEditWidget::syncFrameFromCurrent()
updateFramesDurations();
}
void PoseEditWidget::setFrameCount(int count)
{
if (count == (int)m_frames.size())
return;
setUnsaveState();
count = std::max(count, 1);
m_frames.resize(count);
updateFramesDurations();
updateFramesSettingButton();
if (m_currentFrame >= count) {
setCurrentFrame(count - 1);
}
}
void PoseEditWidget::updateFramesDurations()
{
if (m_frames.empty())
@ -604,6 +633,11 @@ void PoseEditWidget::setEditPoseTurnaroundImageId(QUuid imageId)
m_poseDocument->updateTurnaround(*image);
}
void PoseEditWidget::setEditPoseYtranslationScale(float yTranslationScale)
{
m_yTranslationScale = yTranslationScale;
}
void PoseEditWidget::clearUnsaveState()
{
m_unsaved = false;
@ -620,11 +654,12 @@ void PoseEditWidget::save()
{
if (m_poseId.isNull()) {
m_poseId = QUuid::createUuid();
emit addPose(m_poseId, m_nameEdit->text(), m_frames, m_imageId);
emit addPose(m_poseId, m_nameEdit->text(), m_frames, m_imageId, m_yTranslationScale);
} else if (m_unsaved) {
emit renamePose(m_poseId, m_nameEdit->text());
emit setPoseFrames(m_poseId, m_frames);
emit setPoseTurnaroundImageId(m_poseId, m_imageId);
emit setPoseYtranslationScale(m_poseId, m_yTranslationScale);
}
clearUnsaveState();
}

View File

@ -19,10 +19,11 @@ class PoseEditWidget : public QDialog
{
Q_OBJECT
signals:
void addPose(QUuid poseId, QString name, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames, QUuid turnaroundImageId);
void addPose(QUuid poseId, QString name, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames, QUuid turnaroundImageId, float yTranslationScale);
void removePose(QUuid poseId);
void setPoseFrames(QUuid poseId, std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames);
void setPoseTurnaroundImageId(QUuid poseId, QUuid imageId);
void setPoseYtranslationScale(QUuid poseId, float scale);
void renamePose(QUuid poseId, QString name);
void parametersAdjusted();
public:
@ -38,10 +39,10 @@ public slots:
void setEditPoseName(QString name);
void setEditPoseFrames(std::vector<std::pair<std::map<QString, QString>, std::map<QString, std::map<QString, QString>>>> frames);
void setEditPoseTurnaroundImageId(QUuid imageId);
void setEditPoseYtranslationScale(float yTranslationScale);
void setCurrentFrame(int frame);
void insertFrameAfterCurrentFrame();
void removeCurrentFrame();
void setFrameCount(int count);
void setDuration(float duration);
void updateTitle();
void save();
@ -51,6 +52,7 @@ public slots:
private slots:
void updateFramesSettingButton();
void showFramesSettingPopup(const QPoint &pos);
void showPoseSettingPopup(const QPoint &pos);
void updateFramesDurations();
protected:
QSize sizeHint() const override;
@ -71,6 +73,7 @@ private:
QUuid m_poseId;
bool m_unsaved = false;
QUuid m_imageId;
float m_yTranslationScale = 1.0;
QLineEdit *m_nameEdit = nullptr;
QDoubleSpinBox *m_durationEdit = nullptr;
PoseDocument *m_poseDocument = nullptr;

View File

@ -78,6 +78,7 @@ void PoseManageWidget::showPoseDialog(QUuid poseId)
poseEditWidget->setEditPoseName(pose->name);
poseEditWidget->setEditPoseFrames(pose->frames);
poseEditWidget->setEditPoseTurnaroundImageId(pose->turnaroundImageId);
poseEditWidget->setEditPoseYtranslationScale(pose->yTranslationScale);
poseEditWidget->clearUnsaveState();
}
}

View File

@ -15,6 +15,11 @@ Poser::~Poser()
{
}
void Poser::setYtranslationScale(float scale)
{
m_yTranslationScale = scale;
}
int Poser::findBoneIndex(const QString &name)
{
auto findResult = m_boneNameToIndexMap.find(name);

View File

@ -17,6 +17,7 @@ public:
const std::vector<JointNode> &resultNodes() const;
const JointNodeTree &resultJointNodeTree() const;
std::map<QString, std::map<QString, QString>> &parameters();
void setYtranslationScale(float scale);
virtual void commit();
void reset();
static void fetchChains(const std::vector<QString> &boneNames, std::map<QString, std::vector<QString>> &chains);
@ -25,6 +26,7 @@ protected:
std::map<QString, int> m_boneNameToIndexMap;
JointNodeTree m_jointNodeTree;
std::map<QString, std::map<QString, QString>> m_parameters;
float m_yTranslationScale = 1.0;
};
#endif