|
Biorbd
|
Holder for the marker set. More...
#include <Markers.h>
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::NodeSegment & | marker (unsigned int idx) const |
| Return the marker of index idx. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | marker (const biorbd::utils::String &name) const |
| Return the markers on a segment. More... | |
| std::vector< biorbd::utils::String > | markerNames () const |
| Return the names of all the markers. More... | |
| std::vector< biorbd::utils::String > | technicalMarkerNames () const |
| Return the names of all the technical markers. More... | |
| std::vector< biorbd::utils::String > | anatomicalMarkerNames () 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::NodeSegment > | 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. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | markers (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::NodeSegment > | markersVelocity (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::NodeSegment > | 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. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | technicalMarkers (bool removeAxis=true) |
| Return the technical markers in their respective parent reference frame. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | 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. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | anatomicalMarkers (bool removeAxis=true) |
| Return the anatomical markers in their respective parent reference frame. More... | |
| std::vector< biorbd::rigidbody::NodeSegment > | 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. 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::Matrix > | markersJacobian (const biorbd::rigidbody::GeneralizedCoordinates &Q, bool removeAxis=true, bool updateKin=true) |
| Return the jacobian of the markers. More... | |
| std::vector< biorbd::utils::Matrix > | technicalMarkersJacobian (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::Matrix > | markersJacobian (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. | |
| biorbd::rigidbody::Markers::Markers | ( | const biorbd::rigidbody::Markers & | other | ) |
Construct markers from another marker set.
| other | The other marker set |
Definition at line 21 of file Markers.cpp.
| 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.
| pos | The position of the marker |
| name | The name of the marker |
| parentName | The name of the segment the marker is attached on |
| technical | If the marker is technical |
| anatomical | If the marker is anatomical |
| axesToRemove | Axes to remove while projecting the marker |
| id | The index of the parent segment |
Definition at line 47 of file Markers.cpp.
| std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::anatomicalMarkerNames | ( | ) | const |
Return the names of all the anatomical markers.
Definition at line 473 of file Markers.cpp.
| std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::anatomicalMarkers | ( | bool | removeAxis = true | ) |
Return the anatomical markers in their respective parent reference frame.
| removeAxis | If there are axis to remove from the position variables |
Definition at line 252 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 232 of file Markers.cpp.
| biorbd::rigidbody::Markers biorbd::rigidbody::Markers::DeepCopy | ( | ) | const |
Deep copy of the markers.
Definition at line 32 of file Markers.cpp.
| void biorbd::rigidbody::Markers::DeepCopy | ( | const biorbd::rigidbody::Markers & | other | ) |
Deep copy of the markers.
| other | The markers to copy from |
Definition at line 39 of file Markers.cpp.
| 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.
| markers | The markers to track |
| Qinit | The initial guess for the generalized coordinates |
| Q | The generalized coordinates that tracks the markers |
| removeAxes | If the markers should be projected on the axes |
Definition at line 347 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| node | The position of the marker in its parent reference frame |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 78 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| idx | The index of the marker in the marker set |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 97 of file Markers.cpp.
| std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::marker | ( | const biorbd::utils::String & | name | ) | const |
Return the markers on a segment.
| name | Name of the segment |
Definition at line 66 of file Markers.cpp.
| const biorbd::rigidbody::NodeSegment & biorbd::rigidbody::Markers::marker | ( | unsigned int | idx | ) | const |
Return the marker of index idx.
| idx | The marker we want to return |
Definition at line 60 of file Markers.cpp.
| biorbd::rigidbody::NodeSegment biorbd::rigidbody::Markers::marker | ( | unsigned int | idx, |
| bool | removeAxis | ||
| ) |
Return a marker of index idx in the marker set.
| idx | The index of the marker |
| removeAxis | If there are axis to remove from the position variables |
Definition at line 117 of file Markers.cpp.
| std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::markerNames | ( | ) | const |
Return the names of all the markers.
Definition at line 454 of file Markers.cpp.
| std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::markers | ( | bool | removeAxis = true | ) |
Return all the markers in their respective parent reference frame.
| removeAxis | If there are axis to remove from the position variables |
Definition at line 146 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 129 of file Markers.cpp.
|
protected |
Compute the jacobian of the markers.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
| lookForTechnical | Check if only technical markers are to be computed |
Definition at line 380 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 308 of file Markers.cpp.
| 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.
| Q | The generalized coordinates of the model |
| parentName | The name of the segment the marker lies on |
| p | The position of the point in the parent reference frame |
| updateKin | If the model should be updated |
Definition at line 325 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| Qdot | The generalized velocities |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 182 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| Qdot | The generalized velocities |
| idx | The index of the marker in the marker set |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 157 of file Markers.cpp.
| unsigned int biorbd::rigidbody::Markers::nbAnatomicalMarkers | ( | ) |
Return the number of anatomical markers.
Definition at line 443 of file Markers.cpp.
| unsigned int biorbd::rigidbody::Markers::nbMarkers | ( | ) | const |
Return the number of markers.
Definition at line 286 of file Markers.cpp.
| unsigned int biorbd::rigidbody::Markers::nbMarkers | ( | unsigned int | idxSegment | ) | const |
Return the number of markers on the segment idxSegment.
| idxSegment | The index of the segment |
Definition at line 291 of file Markers.cpp.
| unsigned int biorbd::rigidbody::Markers::nbTechnicalMarkers | ( | ) |
Return the number of technical markers.
Definition at line 413 of file Markers.cpp.
| unsigned int biorbd::rigidbody::Markers::nbTechnicalMarkers | ( | unsigned int | idxSegment | ) |
Return the number of technical markers on the segment idxSegment.
| idxSegment | The index of the segment |
Definition at line 424 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| idx | The index of the segment |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 263 of file Markers.cpp.
| std::vector< biorbd::utils::String > biorbd::rigidbody::Markers::technicalMarkerNames | ( | ) | const |
Return the names of all the technical markers.
Definition at line 463 of file Markers.cpp.
| std::vector< biorbd::rigidbody::NodeSegment > biorbd::rigidbody::Markers::technicalMarkers | ( | bool | removeAxis = true | ) |
Return the technical markers in their respective parent reference frame.
| removeAxis | If there are axis to remove from the position variables |
Definition at line 222 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 202 of file Markers.cpp.
| 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.
| Q | The generalized coordinates |
| removeAxis | If there are axis to remove from the position variables |
| updateKin | If the model should be updated |
Definition at line 316 of file Markers.cpp.
1.8.18