Skip to content
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

Added mesh properties in ModelWriter (meshcolor, meshscale, meshrt) #254

Merged
merged 2 commits into from
Jan 20, 2022
Merged
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
14 changes: 14 additions & 0 deletions include/RigidBody/Mesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,12 @@ class BIORBD_API Mesh
void rotate(
const utils::RotoTrans& rt);

///
/// \brief Get the rotation applied to the vertex
/// \return The Transformation applied to the mesh wrt the parent
///
utils::RotoTrans& getRotation() const;

///
/// \brief Scale the vertex wrt to 0, 0, 0. Warnign, this function is
/// applied when called, meaning that if it is called after rotate, it will
Expand All @@ -108,6 +114,12 @@ class BIORBD_API Mesh
void scale(
const utils::Vector3d& scaler);

///
/// \brief Get the scaling applied to the vertex wrt to 0, 0, 0.
/// \return The scaling applied to the mesh wrt the parent
///
utils::Vector3d& getScale() const;

///
/// \brief Add a face patch to the mesh
/// \param face The face patch to add
Expand Down Expand Up @@ -160,6 +172,8 @@ class BIORBD_API Mesh
m_faces; ///< The faces
std::shared_ptr<utils::Path> m_pathFile; ///< The path to the mesh file
std::shared_ptr<utils::Vector3d> m_patchColor; ///< The color of faces
std::shared_ptr<utils::RotoTrans> m_rotation; ///< The rotation
std::shared_ptr<utils::Vector3d> m_scale; ///< The scale
};

}
Expand Down
14 changes: 14 additions & 0 deletions src/ModelWriter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "Utils/String.h"
#include "Utils/Path.h"
#include "Utils/Matrix3d.h"
#include "Utils/Vector.h"
#include "RigidBody/IMU.h"
#include "RigidBody/NodeSegment.h"
#include "RigidBody/Segment.h"
Expand Down Expand Up @@ -77,6 +78,19 @@ void Writer::writeModel(Model & model,
biorbdModelFile << sep << sep << "meshfile" << sep << model.segment(
i).characteristics().mesh().path().originalPath() <<
std::endl;
biorbdModelFile << sep << sep << "meshcolor" << sep << model.segment(
i).characteristics().mesh().color().transpose() <<
std::endl;
biorbdModelFile << sep << sep << "meshscale" << sep << model.segment(
i).characteristics().mesh().getScale().transpose() <<
std::endl;

biorbdModelFile << sep << sep << "meshrt" << sep <<
utils::RotoTrans::toEulerAngles(model.segment(i).characteristics().mesh().getRotation(),
utils::String("xyz")).transpose() <<
" xyz " <<
model.segment(i).characteristics().mesh().getRotation().trans().transpose() <<
std::endl;
}
biorbdModelFile << sep << "endsegment" << sep << std::endl;
biorbdModelFile << std::endl;
Expand Down
28 changes: 23 additions & 5 deletions src/RigidBody/Mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@ rigidbody::Mesh::Mesh() :
m_vertex(std::make_shared<std::vector<utils::Vector3d>>()),
m_faces(std::make_shared<std::vector<rigidbody::MeshFace>>()),
m_pathFile(std::make_shared<utils::Path>()),
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788))
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788)),
m_rotation(std::make_shared<utils::RotoTrans>(RigidBodyDynamics::Math::Matrix4d::Identity())),
m_scale(std::make_shared<utils::Vector3d>(1.0, 1.0, 1.0))
{

}
Expand All @@ -22,7 +24,9 @@ rigidbody::Mesh::Mesh(
m_vertex(std::make_shared<std::vector<utils::Vector3d>>(other)),
m_faces(std::make_shared<std::vector<rigidbody::MeshFace>>()),
m_pathFile(std::make_shared<utils::Path>()),
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788))
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788)),
m_rotation(std::make_shared<utils::RotoTrans>(RigidBodyDynamics::Math::Matrix4d::Identity())),
m_scale(std::make_shared<utils::Vector3d>(1.0, 1.0, 1.0))
{

}
Expand All @@ -33,7 +37,9 @@ rigidbody::Mesh::Mesh(const std::vector<utils::Vector3d>
m_vertex(std::make_shared<std::vector<utils::Vector3d>>(vertex)),
m_faces(std::make_shared<std::vector<rigidbody::MeshFace>>(faces)),
m_pathFile(std::make_shared<utils::Path>()),
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788))
m_patchColor(std::make_shared<utils::Vector3d>(0.89, 0.855, 0.788)),
m_rotation(std::make_shared<utils::RotoTrans>(RigidBodyDynamics::Math::Matrix4d::Identity())),
m_scale(std::make_shared<utils::Vector3d>(1.0, 1.0, 1.0))
{

}
Expand Down Expand Up @@ -85,22 +91,34 @@ unsigned int rigidbody::Mesh::nbVertex() const

void rigidbody::Mesh::rotate(
const utils::RotoTrans &rt)
{
{
*m_rotation = rt;
for (auto& v : *m_vertex){
v.applyRT(rt);
}
}

utils::RotoTrans &rigidbody::Mesh::getRotation() const
{
return *m_rotation;
}

void rigidbody::Mesh::scale(
const utils::Vector3d &scaler)
{
{
*m_scale = scaler;
for (auto& v: *m_vertex){
v(0) *= scaler(0);
v(1) *= scaler(1);
v(2) *= scaler(2);
}
}

utils::Vector3d &rigidbody::Mesh::getScale() const
{
return *m_scale;
}

unsigned int rigidbody::Mesh::nbFaces()
{
return static_cast<unsigned int>(m_faces->size());
Expand Down