Biorbd
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
biorbd::rigidbody::Markers Class Reference

Holder for the marker set. More...

#include <Markers.h>

Inheritance diagram for biorbd::rigidbody::Markers:
biorbd::Model

Public Member Functions

 Markers ()
 Construct a marker set.
 
 Markers (const biorbd::rigidbody::Markers &other)
 Construct markers from another marker set. More...
 
virtual ~Markers ()
 Destroy class properly.
 
biorbd::rigidbody::Markers DeepCopy () const
 Deep copy of the markers. More...
 
void DeepCopy (const biorbd::rigidbody::Markers &other)
 Deep copy of the markers. More...
 
void addMarker (const biorbd::rigidbody::NodeSegment &pos, const biorbd::utils::String &name, const biorbd::utils::String &parentName, bool technical, bool anatomical, const biorbd::utils::String &axesToRemove, int id=-1)
 Add a marker to the set. More...
 
const biorbd::rigidbody::NodeSegmentmarker (unsigned int idx) const
 Return the marker of index idx. More...
 
std::vector< biorbd::rigidbody::NodeSegmentmarker (const biorbd::utils::String &name) const
 Return the markers on a segment. More...
 
std::vector< biorbd::utils::StringmarkerNames () const
 Return the names of all the markers. More...
 
std::vector< biorbd::utils::StringtechnicalMarkerNames () const
 Return the names of all the technical markers. More...
 
std::vector< biorbd::utils::StringanatomicalMarkerNames () const
 Return the names of all the anatomical markers. More...
 
biorbd::rigidbody::NodeSegment marker (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::NodeSegment &node, bool removeAxis=true, bool updateKin=true)
 Compute and return the position of a marker at given Q in the global reference frame. More...
 
biorbd::rigidbody::NodeSegment marker (const biorbd::rigidbody::GeneralizedCoordinates &Q, unsigned int idx, bool removeAxis=true, bool updateKin=true)
 Compute and return the position of the marker of index idx at given Q in the global reference frame. More...
 
biorbd::rigidbody::NodeSegment marker (unsigned int idx, bool removeAxis)
 Return a marker of index idx in the marker set. More...
 
std::vector< biorbd::rigidbody::NodeSegmentmarkers (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true)
 Return all the markers at a given Q in the global reference frame. More...
 
std::vector< biorbd::rigidbody::NodeSegmentmarkers (bool removeAxis=true)
 Return all the markers in their respective parent reference frame. More...
 
biorbd::rigidbody::NodeSegment markerVelocity (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, unsigned int idx, bool removeAxis=true, bool updateKin=true)
 Return the velocity of a marker. More...
 
std::vector< biorbd::rigidbody::NodeSegmentmarkersVelocity (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::rigidbody::GeneralizedVelocity &Qdot, bool removeAxis=true, bool updateKin=true)
 Return the velocity of all the markers. More...
 
std::vector< biorbd::rigidbody::NodeSegmenttechnicalMarkers (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true)
 Return all the technical markers at a given Q in the global reference frame. More...
 
std::vector< biorbd::rigidbody::NodeSegmenttechnicalMarkers (bool removeAxis=true)
 Return the technical markers in their respective parent reference frame. More...
 
std::vector< biorbd::rigidbody::NodeSegmentanatomicalMarkers (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true)
 Return all the anatomical markers at a given Q in the global reference frame. More...
 
std::vector< biorbd::rigidbody::NodeSegmentanatomicalMarkers (bool removeAxis=true)
 Return the anatomical markers in their respective parent reference frame. More...
 
std::vector< biorbd::rigidbody::NodeSegmentsegmentMarkers (const biorbd::rigidbody::GeneralizedCoordinates &Q, unsigned int idx, bool removeAxis=true, bool updateKin=true)
 Return all the markers of the segment idx at a given Q in the global reference frame. More...
 
unsigned int nbMarkers () const
 Return the number of markers. More...
 
unsigned int nbMarkers (unsigned int idxSegment) const
 Return the number of markers on the segment idxSegment. More...
 
unsigned int nbTechnicalMarkers ()
 Return the number of technical markers. More...
 
unsigned int nbTechnicalMarkers (unsigned int idxSegment)
 Return the number of technical markers on the segment idxSegment. More...
 
unsigned int nbAnatomicalMarkers ()
 Return the number of anatomical markers. More...
 
std::vector< biorbd::utils::MatrixmarkersJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true)
 Return the jacobian of the markers. More...
 
std::vector< biorbd::utils::MatrixtechnicalMarkersJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true)
 Return the jacobian of the technical markers. More...
 
biorbd::utils::Matrix markersJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, const biorbd::utils::String &parentName, const biorbd::rigidbody::NodeSegment &p, bool updateKin)
 Return the jacobian of a chosen marker. More...
 
bool inverseKinematics (const std::vector< biorbd::rigidbody::NodeSegment > &markers, const biorbd::rigidbody::GeneralizedCoordinates &Qinit, biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxes=true)
 Performs an inverse kinematics. More...
 

Protected Member Functions

std::vector< biorbd::utils::MatrixmarkersJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis, bool updateKin, bool lookForTechnical)
 Compute the jacobian of the markers. More...
 

Protected Attributes

std::shared_ptr< std::vector< biorbd::rigidbody::NodeSegment > > m_marks
 The markers.
 

Detailed Description

Holder for the marker set.

Definition at line 22 of file Markers.h.

Constructor & Destructor Documentation

◆ Markers()

biorbd::rigidbody::Markers::Markers ( const biorbd::rigidbody::Markers other)

Construct markers from another marker set.

Parameters
otherThe other marker set

Definition at line 21 of file Markers.cpp.

Member Function Documentation

◆ addMarker()

void biorbd::rigidbody::Markers::addMarker ( const biorbd::rigidbody::NodeSegment pos,
const biorbd::utils::String name,
const biorbd::utils::String parentName,
bool  technical,
bool  anatomical,
const biorbd::utils::String axesToRemove,
int  id = -1 
)

Add a marker to the set.

Parameters
posThe position of the marker
nameThe name of the marker
parentNameThe name of the segment the marker is attached on
technicalIf the marker is technical
anatomicalIf the marker is anatomical
axesToRemoveAxes to remove while projecting the marker
idThe index of the parent segment

Definition at line 47 of file Markers.cpp.

◆ anatomicalMarkerNames()

std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::anatomicalMarkerNames ( ) const

Return the names of all the anatomical markers.

Returns
The names of the anatomical markers

Definition at line 473 of file Markers.cpp.

◆ anatomicalMarkers() [1/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::anatomicalMarkers ( bool  removeAxis = true)

Return the anatomical markers in their respective parent reference frame.

Parameters
removeAxisIf there are axis to remove from the position variables
Returns
A vector of all the anatomical markers in their parent reference frame

Definition at line 252 of file Markers.cpp.

◆ anatomicalMarkers() [2/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::anatomicalMarkers ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis = true,
bool  updateKin = true 
)

Return all the anatomical markers at a given Q in the global reference frame.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
A vector of all the anatomical markers

Definition at line 232 of file Markers.cpp.

◆ DeepCopy() [1/2]

biorbd::rigidbody::Markers biorbd::rigidbody::Markers::DeepCopy ( ) const

Deep copy of the markers.

Returns
Deep copy of the markers

Definition at line 32 of file Markers.cpp.

◆ DeepCopy() [2/2]

void biorbd::rigidbody::Markers::DeepCopy ( const biorbd::rigidbody::Markers other)

Deep copy of the markers.

Parameters
otherThe markers to copy from

Definition at line 39 of file Markers.cpp.

◆ inverseKinematics()

bool biorbd::rigidbody::Markers::inverseKinematics ( const std::vector< biorbd::rigidbody::NodeSegment > &  markers,
const biorbd::rigidbody::GeneralizedCoordinates Qinit,
biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxes = true 
)

Performs an inverse kinematics.

Parameters
markersThe markers to track
QinitThe initial guess for the generalized coordinates
QThe generalized coordinates that tracks the markers
removeAxesIf the markers should be projected on the axes

Definition at line 347 of file Markers.cpp.

◆ marker() [1/5]

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Markers::marker ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::NodeSegment node,
bool  removeAxis = true,
bool  updateKin = true 
)

Compute and return the position of a marker at given Q in the global reference frame.

Parameters
QThe generalized coordinates
nodeThe position of the marker in its parent reference frame
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The marker in the global reference frame

Definition at line 78 of file Markers.cpp.

◆ marker() [2/5]

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Markers::marker ( const biorbd::rigidbody::GeneralizedCoordinates Q,
unsigned int  idx,
bool  removeAxis = true,
bool  updateKin = true 
)

Compute and return the position of the marker of index idx at given Q in the global reference frame.

Parameters
QThe generalized coordinates
idxThe index of the marker in the marker set
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The marker idx in the global reference frame

Definition at line 97 of file Markers.cpp.

◆ marker() [3/5]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::marker ( const biorbd::utils::String name) const

Return the markers on a segment.

Parameters
nameName of the segment
Returns
The markers on the segment

Definition at line 66 of file Markers.cpp.

◆ marker() [4/5]

const biorbd::rigidbody::NodeSegment & biorbd::rigidbody::Markers::marker ( unsigned int  idx) const

Return the marker of index idx.

Parameters
idxThe marker we want to return
Returns
The marker

Definition at line 60 of file Markers.cpp.

◆ marker() [5/5]

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Markers::marker ( unsigned int  idx,
bool  removeAxis 
)

Return a marker of index idx in the marker set.

Parameters
idxThe index of the marker
removeAxisIf there are axis to remove from the position variables
Returns
The marker of index idx

Definition at line 117 of file Markers.cpp.

◆ markerNames()

std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::markerNames ( ) const

Return the names of all the markers.

Returns
The names of the markers

Definition at line 454 of file Markers.cpp.

◆ markers() [1/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::markers ( bool  removeAxis = true)

Return all the markers in their respective parent reference frame.

Parameters
removeAxisIf there are axis to remove from the position variables
Returns
All the markers

Definition at line 146 of file Markers.cpp.

◆ markers() [2/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::markers ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis = true,
bool  updateKin = true 
)

Return all the markers at a given Q in the global reference frame.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
All the markers in the global reference frame

Definition at line 129 of file Markers.cpp.

◆ markersJacobian() [1/3]

std::vector< biorbd::utils::Matrix > biorbd::rigidbody::Markers::markersJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis,
bool  updateKin,
bool  lookForTechnical 
)
protected

Compute the jacobian of the markers.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
lookForTechnicalCheck if only technical markers are to be computed
Returns
The jacobian of the markers

Definition at line 380 of file Markers.cpp.

◆ markersJacobian() [2/3]

std::vector< biorbd::utils::Matrix > biorbd::rigidbody::Markers::markersJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis = true,
bool  updateKin = true 
)

Return the jacobian of the markers.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The jacobian of the markers

Definition at line 308 of file Markers.cpp.

◆ markersJacobian() [3/3]

biorbd::utils::Matrix biorbd::rigidbody::Markers::markersJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::utils::String parentName,
const biorbd::rigidbody::NodeSegment p,
bool  updateKin 
)

Return the jacobian of a chosen marker.

Parameters
QThe generalized coordinates of the model
parentNameThe name of the segment the marker lies on
pThe position of the point in the parent reference frame
updateKinIf the model should be updated
Returns
The jacobian of the chosen marker

Definition at line 325 of file Markers.cpp.

◆ markersVelocity()

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::markersVelocity ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
bool  removeAxis = true,
bool  updateKin = true 
)

Return the velocity of all the markers.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The velocity of all the markers

Definition at line 182 of file Markers.cpp.

◆ markerVelocity()

biorbd::rigidbody::NodeSegment biorbd::rigidbody::Markers::markerVelocity ( const biorbd::rigidbody::GeneralizedCoordinates Q,
const biorbd::rigidbody::GeneralizedVelocity Qdot,
unsigned int  idx,
bool  removeAxis = true,
bool  updateKin = true 
)

Return the velocity of a marker.

Parameters
QThe generalized coordinates
QdotThe generalized velocities
idxThe index of the marker in the marker set
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The velocity of a marker

Definition at line 157 of file Markers.cpp.

◆ nbAnatomicalMarkers()

unsigned int biorbd::rigidbody::Markers::nbAnatomicalMarkers ( )

Return the number of anatomical markers.

Returns
The number of anatomical markers

Definition at line 443 of file Markers.cpp.

◆ nbMarkers() [1/2]

unsigned int biorbd::rigidbody::Markers::nbMarkers ( ) const

Return the number of markers.

Returns
The number of markers

Definition at line 286 of file Markers.cpp.

◆ nbMarkers() [2/2]

unsigned int biorbd::rigidbody::Markers::nbMarkers ( unsigned int  idxSegment) const

Return the number of markers on the segment idxSegment.

Parameters
idxSegmentThe index of the segment
Returns
The number of markers of segment idxSegment

Definition at line 291 of file Markers.cpp.

◆ nbTechnicalMarkers() [1/2]

unsigned int biorbd::rigidbody::Markers::nbTechnicalMarkers ( )

Return the number of technical markers.

Returns
The number of technical markers

Definition at line 413 of file Markers.cpp.

◆ nbTechnicalMarkers() [2/2]

unsigned int biorbd::rigidbody::Markers::nbTechnicalMarkers ( unsigned int  idxSegment)

Return the number of technical markers on the segment idxSegment.

Parameters
idxSegmentThe index of the segment
Returns
The number of technical markers of segment idxSegment

Definition at line 424 of file Markers.cpp.

◆ segmentMarkers()

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::segmentMarkers ( const biorbd::rigidbody::GeneralizedCoordinates Q,
unsigned int  idx,
bool  removeAxis = true,
bool  updateKin = true 
)

Return all the markers of the segment idx at a given Q in the global reference frame.

Parameters
QThe generalized coordinates
idxThe index of the segment
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
All the markers of the segment idx

Definition at line 263 of file Markers.cpp.

◆ technicalMarkerNames()

std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::technicalMarkerNames ( ) const

Return the names of all the technical markers.

Returns
The names of the technical markers

Definition at line 463 of file Markers.cpp.

◆ technicalMarkers() [1/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::technicalMarkers ( bool  removeAxis = true)

Return the technical markers in their respective parent reference frame.

Parameters
removeAxisIf there are axis to remove from the position variables
Returns
A vector of all the technical markers in their parent reference frame

Definition at line 222 of file Markers.cpp.

◆ technicalMarkers() [2/2]

std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::technicalMarkers ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis = true,
bool  updateKin = true 
)

Return all the technical markers at a given Q in the global reference frame.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
A vector of all the technical markers

Definition at line 202 of file Markers.cpp.

◆ technicalMarkersJacobian()

std::vector< biorbd::utils::Matrix > biorbd::rigidbody::Markers::technicalMarkersJacobian ( const biorbd::rigidbody::GeneralizedCoordinates Q,
bool  removeAxis = true,
bool  updateKin = true 
)

Return the jacobian of the technical markers.

Parameters
QThe generalized coordinates
removeAxisIf there are axis to remove from the position variables
updateKinIf the model should be updated
Returns
The jacobian of the technical markers

Definition at line 316 of file Markers.cpp.


The documentation for this class was generated from the following files: