class mrpt::viz::CAnimatedAssimpModel
Overview
Extension of CAssimpModel with skeletal animation support.
Supports models that contain bone hierarchies and keyframed animations (FBX, glTF/GLB, Collada, etc. via Assimp).
CPU-side vertex skinning is performed each time the animation time changes: bind-pose vertex positions are stored on first load and then transformed through the active bone matrices every frame.
Usage:
auto model = CAnimatedAssimpModel::Create(); model->loadScene("character.glb"); // In simulation loop: model->setAnimationTime(simTime); // updates bone transforms & rebuilds geometry
#include <mrpt/viz/CAnimatedAssimpModel.h> class CAnimatedAssimpModel: public mrpt::viz::CAssimpModel { public: // typedefs typedef std::shared_ptr<mrpt::viz ::CAnimatedAssimpModel> Ptr; typedef std::shared_ptr<const mrpt::viz ::CAnimatedAssimpModel> ConstPtr; typedef std::unique_ptr<mrpt::viz ::CAnimatedAssimpModel> UniquePtr; typedef std::unique_ptr<const mrpt::viz ::CAnimatedAssimpModel> ConstUniquePtr; // structs struct Animation; struct Bone; struct BoneAnimation; struct MeshBindPose; struct QuatKey; struct VectorKey; struct VertexBoneData; // fields static constexpr const char* className = "mrpt::viz" "::" "CAnimatedAssimpModel"; // construction CAnimatedAssimpModel(); // methods static constexpr auto getClassName(); static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); static std::shared_ptr<CObject> CreateObject(); template <typename... Args> static Ptr Create(Args&&... args); template <typename Alloc, typename... Args> static Ptr CreateAlloc( const Alloc& alloc, Args&&... args ); template <typename... Args> static UniquePtr CreateUnique(Args&&... args); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual mrpt::rtti::CObject* clone() const; static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPosePDF& o); static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPointPDF& o); static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPose3DPDF& o); static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPose3DQuatPDF& o); void clear(); const std::string& getModelPath() const; uint32_t getModelLoadFlags() const; void setSplitTrianglesRenderingBBox(float bbox_size); float getSplitTrianglesRenderingBBox() const; size_t getTexturedMeshCount() const; size_t getNonTexturedTriangleCount() const; size_t getTotalVertexCount() const; size_t getTotalTriangleCount() const; std::vector<TextureInfo> getTextureInfo() const; virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const; virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const; CVisualObject& setColor_u8(uint8_t R, uint8_t G, uint8_t B, uint8_t A = 255); void setName(const std::string& n); std::string getName() const; bool isVisible() const; void setVisibility(bool visible = true); bool castShadows() const; void castShadows(bool doCast = true); void enableShowName(bool showName = true); bool isShowNameEnabled() const; CVisualObject& setPose(const mrpt::poses::CPose3D& o); CVisualObject& setPose(const mrpt::poses::CPose2D& o); CVisualObject& setPose(const mrpt::math::TPose3D& o); CVisualObject& setPose(const mrpt::math::TPose2D& o); CVisualObject& setPose(const mrpt::poses::CPoint3D& o); CVisualObject& setPose(const mrpt::poses::CPoint2D& o); mrpt::math::TPose3D getPose() const; mrpt::poses::CPose3D getCPose() const; CVisualObject& setLocation(double x, double y, double z); CVisualObject& setLocation(const mrpt::math::TPoint3D& p); mrpt::img::TColorf getColor() const; mrpt::img::TColor getColor_u8() const; CVisualObject& setColorA(const float a); float materialShininess() const; void materialShininess(float shininess); float materialSpecularExponent() const; void materialSpecularExponent(float exponent); mrpt::img::TColorf materialEmissive() const; void materialEmissive(const mrpt::img::TColorf& color); CVisualObject& setScale(float s); CVisualObject& setScale(float sx, float sy, float sz); float getScaleX() const; float getScaleY() const; float getScaleZ() const; CVisualObject& setColor(const mrpt::img::TColorf& c); CVisualObject& setColor(float R, float G, float B, float A = 1); void loadScene(const std::string& file_name, int flags = LoadFlags::RealTimeMaxQuality|LoadFlags::FlipUVs|LoadFlags::Verbose); void setAnimationTime(double timeSeconds); double getAnimationDuration(size_t animIndex = 0) const; size_t getAnimationCount() const; std::string getAnimationName(size_t animIndex) const; void setActiveAnimation(size_t animIndex); void setActiveAnimation(const std::string& animName); void setLooping(bool loop); double getAnimationProgress() const; size_t getBoneCount() const; int getBoneIndex(const std::string& boneName) const; void setBoneLocalTransform(size_t boneIndex, const mrpt::math::CMatrixDouble44& localTransform); void clearBoneOverrides(); template <class T> void insertCollection(const T& objs); void insert(const CVisualObject::Ptr& newObject); template <class T_it> void insert(const T_it& begin, const T_it& end); size_t size() const; bool empty() const; CVisualObject::Ptr getByName(const std::string& str); template <typename T> T::ConstPtr getByClass(size_t ith = 0) const; void removeObject(const CVisualObject::Ptr& obj); void dumpListOfObjects(std::vector<std::string>& lst) const; mrpt::containers::yaml asYAML() const; virtual CVisualObject& setColorA_u8(const uint8_t a); virtual bool cullElegible() const; virtual void toYAMLMap(mrpt::containers::yaml& propertiesMap) const; virtual bool isCompositeObject() const; virtual const std::deque<std::shared_ptr<CVisualObject>>& getInternalChildren() const; void notifyChange() const; void clearChangedFlag() const; bool hasToUpdateBuffers() const; uint64_t dataVersion() const; bool hasToUpdateBuffersSince(uint64_t sinceVersion) const; virtual void updateBuffers() const; auto getBoundingBox() const; auto getBoundingBoxLocal() const; virtual mrpt::math::TPoint3Df getLocalRepresentativePoint() const; void setLocalRepresentativePoint(const mrpt::math::TPoint3Df& p); mrpt::viz::CText& labelObject() const; std::shared_ptr<mrpt::viz::CText> labelObjectPtr() const; };
Inherited Members
public: // typedefs typedef std::shared_ptr<CObject> Ptr; typedef std::shared_ptr<const CObject> ConstPtr; typedef std::shared_ptr<CSerializable> Ptr; typedef std::shared_ptr<const CSerializable> ConstPtr; typedef std::shared_ptr<mrpt::viz ::CSetOfObjects> Ptr; typedef std::shared_ptr<const mrpt::viz ::CSetOfObjects> ConstPtr; typedef std::unique_ptr<mrpt::viz ::CSetOfObjects> UniquePtr; typedef std::unique_ptr<const mrpt::viz ::CSetOfObjects> ConstUniquePtr; typedef ListVisualObjects::const_iterator const_iterator; typedef ListVisualObjects::iterator iterator; typedef std::shared_ptr<mrpt::viz ::CAssimpModel> Ptr; typedef std::shared_ptr<const mrpt::viz ::CAssimpModel> ConstPtr; typedef std::unique_ptr<mrpt::viz ::CAssimpModel> UniquePtr; typedef std::unique_ptr<const mrpt::viz ::CAssimpModel> ConstUniquePtr; // structs struct PoseAndScale; struct State; struct AssimpSceneWrapper; struct LoadFlags; struct LoadedTexture; struct TextureInfo; // fields static constexpr const char* className = "mrpt::viz" "::" "CSetOfObjects"; static constexpr const char* className = "mrpt::viz" "::" "CAssimpModel"; // methods static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; static constexpr auto getClassName(); static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); static std::shared_ptr<CObject> CreateObject(); template <typename... Args> static Ptr Create(Args&&... args); template <typename Alloc, typename... Args> static Ptr CreateAlloc( const Alloc& alloc, Args&&... args ); template <typename... Args> static UniquePtr CreateUnique(Args&&... args); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual mrpt::rtti::CObject* clone() const; const_iterator begin() const; const_iterator end() const; iterator begin(); iterator end(); void clear(); template <typename T> T::Ptr getByClass(size_t ith = 0); virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const; virtual CVisualObject& setColor_u8(const mrpt::img::TColor& c); bool contains(const CVisualObject::Ptr& obj) const; virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const; static constexpr auto getClassName(); static const mrpt::rtti::TRuntimeClassId& GetRuntimeClassIdStatic(); static std::shared_ptr<CObject> CreateObject(); template <typename... Args> static Ptr Create(Args&&... args); template <typename Alloc, typename... Args> static Ptr CreateAlloc( const Alloc& alloc, Args&&... args ); template <typename... Args> static UniquePtr CreateUnique(Args&&... args); virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const; virtual mrpt::rtti::CObject* clone() const; void loadScene(const std::string& file_name, int flags = LoadFlags::RealTimeMaxQuality|LoadFlags::FlipUVs|LoadFlags::Verbose); CAssimpModel& operator = (CAssimpModel&&);
Typedefs
typedef std::shared_ptr<mrpt::viz ::CAnimatedAssimpModel> Ptr
A type for the associated smart pointer.
Methods
virtual const mrpt::rtti::TRuntimeClassId* GetRuntimeClass() const
Returns information about the class of an object in runtime.
virtual mrpt::rtti::CObject* clone() const
Returns a deep copy (clone) of the object, indepently of its class.
static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPosePDF& o)
Returns a representation of a the PDF - this is just an auxiliary function, it’s more natural to call mrpt::poses::CPosePDF::getAs3DObject
static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPointPDF& o)
Returns a representation of a the PDF - this is just an auxiliary function, it’s more natural to call mrpt::poses::CPointPDF::getAs3DObject
static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPose3DPDF& o)
Returns a representation of a the PDF - this is just an auxiliary function, it’s more natural to call mrpt::poses::CPose3DPDF::getAs3DObject
static CSetOfObjects::Ptr posePDF2opengl(const mrpt::poses::CPose3DQuatPDF& o)
Returns a representation of a the PDF - this is just an auxiliary function, it’s more natural to call mrpt::poses::CPose3DQuatPDF::getAs3DObject
void clear()
Clear the loaded model and all child objects.
const std::string& getModelPath() const
Returns the path of the currently loaded model, or empty string if none.
uint32_t getModelLoadFlags() const
Returns the flags used when loading the current model.
void setSplitTrianglesRenderingBBox(float bbox_size)
Enable (or disable if set to 0.0f) splitting of textured triangles into separate renderable objects based on spatial bounding boxes.
This is required only for semi-transparent objects with overlapping regions, to ensure correct depth sorting during rendering.
Parameters:
bbox_size |
Size of the bounding box for splitting (0.0 = disabled) |
float getSplitTrianglesRenderingBBox() const
Returns the current triangle splitting bbox size (0.0 = disabled)
size_t getTexturedMeshCount() const
Returns the number of textured mesh groups in the loaded model.
size_t getNonTexturedTriangleCount() const
Returns the number of non-textured triangles in the model.
size_t getTotalVertexCount() const
Returns the total vertex count across all meshes.
size_t getTotalTriangleCount() const
Returns the total triangle count across all meshes.
std::vector<TextureInfo> getTextureInfo() const
Returns information about all textures in the model.
virtual mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const
Must be implemented by derived classes to provide the updated bounding box in the object local frame of coordinates.
This will be called only once after each time the derived class reports to notifyChange() that the object geometry changed.
See also:
getBoundingBox(), getBoundingBoxLocal(), getBoundingBoxLocalf()
virtual bool traceRay(const mrpt::poses::CPose3D& o, double& dist) const
Simulation of ray-trace, given a pose.
Returns true if the ray effectively collisions with the object (returning the distance to the origin of the ray in “dist”), or false in other case. “dist” variable yields undefined behaviour when false is returned
CVisualObject& setColor_u8(uint8_t R, uint8_t G, uint8_t B, uint8_t A = 255)
Set the color components of this object (R,G,B,Alpha, in the range 0-255)
Returns:
a ref to this
void setName(const std::string& n)
Changes the name of the object.
std::string getName() const
Returns the name of the object.
bool isVisible() const
Is the object visible?
See also:
void setVisibility(bool visible = true)
Set object visibility (default=true)
See also:
bool castShadows() const
Does the object cast shadows? (default=true)
void castShadows(bool doCast = true)
Enable/disable casting shadows by this object (default=true)
void enableShowName(bool showName = true)
Enables or disables showing the name of the object as a label when rendering.
bool isShowNameEnabled() const
See also:
CVisualObject& setPose(const mrpt::poses::CPose3D& o)
Defines the SE(3) (pose=translation+rotation) of the object with respect to its parent.
CVisualObject& setPose(const mrpt::poses::CPose2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CVisualObject& setPose(const mrpt::math::TPose3D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CVisualObject& setPose(const mrpt::math::TPose2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CVisualObject& setPose(const mrpt::poses::CPoint3D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CVisualObject& setPose(const mrpt::poses::CPoint2D& o)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
mrpt::math::TPose3D getPose() const
Returns the 3D pose of the object as TPose3D.
mrpt::poses::CPose3D getCPose() const
Returns a const ref to the 3D pose of the object as mrpt::poses::CPose3D (which explicitly contains the 3x3 rotation matrix)
CVisualObject& setLocation(double x, double y, double z)
Changes the location of the object, keeping untouched the orientation.
Returns:
a ref to this
CVisualObject& setLocation(const mrpt::math::TPoint3D& p)
Changes the location of the object, keeping untouched the orientation.
Returns:
a ref to this
mrpt::img::TColorf getColor() const
Get color components as floats in the range [0,1].
mrpt::img::TColor getColor_u8() const
Get color components as uint8_t in the range [0,255].
CVisualObject& setColorA(const float a)
Set alpha (transparency) color component in the range [0,1].
Returns:
a ref to this
float materialShininess() const
Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)
void materialShininess(float shininess)
Material shininess (for specular lights in shaders that support it), between 0.0f (none) to 1.0f (shiny)
float materialSpecularExponent() const
Blinn-Phong specular exponent.
Higher values produce a smaller, sharper specular highlight. Typical values: 8 (rough), 32 (default), 128 (metal).
void materialSpecularExponent(float exponent)
Blinn-Phong specular exponent.
Higher values produce a smaller, sharper specular highlight. Typical values: 8 (rough), 32 (default), 128 (metal).
mrpt::img::TColorf materialEmissive() const
Emissive color: light emitted by the object regardless of scene lighting.
Default is black (no emission). Useful for displays, indicator lights, laser beams, warning signs, etc. The emissive term is added to the final lighting equation as: finalColor = emissive + (ambient + diffuse + specular) * materialColor
void materialEmissive(const mrpt::img::TColorf& color)
This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.
CVisualObject& setScale(float s)
Scale to apply to the object, in all three axes (default=1)
Returns:
a ref to this
CVisualObject& setScale(float sx, float sy, float sz)
Scale to apply to the object in each axis (default=1)
Returns:
a ref to this
float getScaleX() const
Get the current scaling factor in one axis.
float getScaleY() const
Get the current scaling factor in one axis.
float getScaleZ() const
Get the current scaling factor in one axis.
CVisualObject& setColor(const mrpt::img::TColorf& c)
Changes the default object color.
Returns:
a ref to this
CVisualObject& setColor(float R, float G, float B, float A = 1)
Set the color components of this object (R,G,B,Alpha, in the range 0-1)
Returns:
a ref to this
void loadScene(const std::string& file_name, int flags = LoadFlags::RealTimeMaxQuality|LoadFlags::FlipUVs|LoadFlags::Verbose)
Loads a 3D scene and extracts skeleton/animation data.
void setAnimationTime(double timeSeconds)
Set current animation time in seconds.
Updates all bone transforms for the active animation and rebuilds the mesh geometry with skinned positions.
double getAnimationDuration(size_t animIndex = 0) const
Get animation duration in seconds.
size_t getAnimationCount() const
Get number of animations in the model.
std::string getAnimationName(size_t animIndex) const
Get animation name by index.
void setActiveAnimation(size_t animIndex)
Select which animation to play (by index).
void setActiveAnimation(const std::string& animName)
Select which animation to play (by name).
Does nothing if the name is not found.
void setLooping(bool loop)
Enable/disable animation looping.
double getAnimationProgress() const
Get current normalized animation progress [0,1].
size_t getBoneCount() const
Get number of bones.
int getBoneIndex(const std::string& boneName) const
Get bone index by name, or -1 if not found.
void setBoneLocalTransform(size_t boneIndex, const mrpt::math::CMatrixDouble44& localTransform)
Override a bone’s local transform (for procedural animation).
void clearBoneOverrides()
Clear all bone overrides, return to animation-driven transforms.
template <class T> void insertCollection(const T& objs)
Inserts a set of objects into the list.
void insert(const CVisualObject::Ptr& newObject)
Insert a new object to the list.
template <class T_it> void insert(const T_it& begin, const T_it& end)
Inserts a set of objects, bounded by iterators, into the list.
size_t size() const
Returns number of objects.
bool empty() const
Returns true if there are no objects.
CVisualObject::Ptr getByName(const std::string& str)
Returns the first object with a given name, or a nullptr pointer if not found.
template <typename T> T::ConstPtr getByClass(size_t ith = 0) const
Returns the i’th object of a given class (or of a descendant class), or nullptr (an empty smart pointer) if not found.
Example:
CSphere::Ptr obs = myscene.getByClass<CSphere>();
By default (ith=0), the first observation is returned.
void removeObject(const CVisualObject::Ptr& obj)
Removes the given object from the scene (it also deletes the object to free its memory).
void dumpListOfObjects(std::vector<std::string>& lst) const
Retrieves a list of all objects in text form.
Deprecated Prefer asYAML() (since MRPT 2.1.3)
mrpt::containers::yaml asYAML() const
Prints all objects in human-readable YAML form.
(New in MRPT 2.1.3)
virtual CVisualObject& setColorA_u8(const uint8_t a)
Set alpha (transparency) color component in the range [0,255].
Returns:
a ref to this
virtual bool cullElegible() const
Return false if this object should never be checked for being culled out (=not rendered if its bbox are out of the screen limits).
For example, skyboxes or other special effects.
virtual void toYAMLMap(mrpt::containers::yaml& propertiesMap) const
Used from Scene::asYAML().
(New in MRPT 2.4.2)
virtual bool isCompositeObject() const
Should return true if enqueueForRenderRecursive() is defined since the object has inner children.
Examples: CSetOfObjects, CAssimpModel.
virtual const std::deque<std::shared_ptr<CVisualObject>>& getInternalChildren() const
Returns internal children for composite objects (e.g.
CAxis text labels). Only meaningful if isCompositeObject() returns true. Not for CSetOfObjects — those are handled as containers.
void notifyChange() const
Call to enable calling renderUpdateBuffers() before the next render() rendering iteration.
See also:
void clearChangedFlag() const
Reset the dirty flag set with notifyChange().
Deprecated Prefer using the version-counter API: dataVersion() / hasToUpdateBuffersSince(). Kept for backwards compatibility; now a no-op.
bool hasToUpdateBuffers() const
Returns whether notifyChange() has been invoked since the last call to renderUpdateBuffers(), meaning the latter needs to be called again before rendering.
Prefer hasToUpdateBuffersSince() for multi-consumer scenarios.
uint64_t dataVersion() const
Returns the current data version counter.
Incremented on each notifyChange() call. Use this with hasToUpdateBuffersSince() for multi-consumer dirty tracking.
bool hasToUpdateBuffersSince(uint64_t sinceVersion) const
Returns true if this object’s data has changed since the given version.
Each consumer (e.g., CompiledScene) should store the last version it processed and pass it here.
virtual void updateBuffers() const
Called by the rendering system to update internal geometry buffers.
Derived classes should override this to populate their data buffers (triangles, points, lines) when the object geometry changes.
This is called automatically when hasToUpdateBuffers() returns true, which happens after notifyChange() was called.
The base implementation does nothing; derived classes should override.
Thread safety: implementations should lock the appropriate mutexes when writing to shared buffers.
auto getBoundingBox() const
Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e.
if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()
auto getBoundingBoxLocal() const
Evaluates the bounding box of this object (including possible children) in the coordinate frame of my parent object, i.e.
if this object pose changes, the bbox returned here will change too. This is in contrast with the local bbox returned by getBoundingBoxLocal()
virtual mrpt::math::TPoint3Df getLocalRepresentativePoint() const
Provide a representative point (in object local coordinates), used to sort objects by eye-distance while rendering with transparencies (Default=[0,0,0])
void setLocalRepresentativePoint(const mrpt::math::TPoint3Df& p)
See getLocalRepresentativePoint()
mrpt::viz::CText& labelObject() const
Returns or constructs (in its first invocation) the associated mrpt::viz::CText object representing the label of the object.
See also:
std::shared_ptr<mrpt::viz::CText> labelObjectPtr() const
Returns the shared_ptr to the label object (creating it if needed).
See also: