1 #define BIORBD_API_EXPORTS
2 #include "RigidBody/Markers.h"
4 #include <rbdl/Model.h>
5 #include <rbdl/Kinematics.h>
6 #include "Utils/String.h"
7 #include "Utils/Matrix.h"
8 #include "RigidBody/GeneralizedCoordinates.h"
9 #include "RigidBody/GeneralizedVelocity.h"
10 #include "RigidBody/Joints.h"
11 #include "RigidBody/NodeSegment.h"
12 #include "RigidBody/Segment.h"
16 m_marks(std::make_shared<std::vector<biorbd::rigidbody::
NodeSegment>>())
22 m_marks(other.m_marks)
41 m_marks->resize(other.
m_marks->size());
42 for (
unsigned int i=0; i<other.
m_marks->size(); ++i)
43 (*m_marks)[i] = (*other.
m_marks)[i].DeepCopy();
57 m_marks->push_back(tp);
61 unsigned int idx)
const
63 return (*m_marks)[idx];
69 std::vector<biorbd::rigidbody::NodeSegment> pos;
70 for (
unsigned int i=0; i<nbMarkers(); ++i)
71 if (!marker(i).parent().compare(name))
72 pos.push_back(marker(i));
89 unsigned int id = model.GetBodyId(n.
parent().c_str());
109 unsigned int id = model.GetBodyId(node.
parent().c_str());
139 std::vector<biorbd::rigidbody::NodeSegment> pos;
140 for (
unsigned int i=0; i<nbMarkers(); ++i)
141 pos.push_back(marker(Q, i, removeAxis,
false));
149 std::vector<biorbd::rigidbody::NodeSegment> pos;
150 for (
unsigned int i=0; i<nbMarkers(); ++i)
151 pos.push_back(marker(i, removeAxis));
172 unsigned int id(model.GetBodyId(node.
parent().c_str()));
194 std::vector<biorbd::rigidbody::NodeSegment> pos;
195 for (
unsigned int i=0; i<nbMarkers(); ++i)
196 pos.push_back(markerVelocity(Q, Qdot, i, removeAxis,
false));
213 std::vector<biorbd::rigidbody::NodeSegment> pos;
214 for (
unsigned int i=0; i<nbMarkers(); ++i) {
215 if ( marker(i).isTechnical() ) {
216 pos.push_back(marker(Q, i, removeAxis,
false));
225 std::vector<biorbd::rigidbody::NodeSegment> pos;
226 for (
unsigned int i=0; i<nbMarkers(); ++i)
227 if ( marker(i).isTechnical() )
228 pos.push_back(marker(i, removeAxis));
243 std::vector<biorbd::rigidbody::NodeSegment> pos;
244 for (
unsigned int i=0; i<nbMarkers(); ++i) {
245 if ( marker(i).isAnatomical() ) {
246 pos.push_back(marker(Q, i, removeAxis,
false));
254 std::vector<biorbd::rigidbody::NodeSegment> pos;
255 for (
unsigned int i=0; i<nbMarkers(); ++i)
256 if ( marker(i).isAnatomical() )
257 pos.push_back(marker(i, removeAxis));
277 std::vector<biorbd::rigidbody::NodeSegment> pos;
278 for (
unsigned int i=0; i<nbMarkers(); ++i)
279 if ((*m_marks)[i].parent().compare(name))
280 pos.push_back(marker(Q,i,removeAxis,
false));
288 return static_cast<unsigned int>(m_marks->size());
300 for (
unsigned int i=0; i<nbMarkers(); ++i)
301 if ((*m_marks)[i].parent().compare(name))
313 return markersJacobian(Q, removeAxis, updateKin,
false);
321 return markersJacobian(Q, removeAxis, updateKin,
true);
340 unsigned int id = model.GetBodyId(parentName.c_str());
341 RigidBodyDynamics::CalcPointJacobian(model, Q,
id, p, G,
false);
346 #ifndef BIORBD_USE_CASADI_MATH
348 const std::vector<biorbd::rigidbody::NodeSegment> &markers,
357 std::vector<biorbd::rigidbody::NodeSegment> body_point(
358 technicalMarkers(removeAxes));
359 std::vector<RigidBodyDynamics::Math::Vector3d> body_pointEigen;
360 for (
unsigned int i=0; i<body_point.size(); ++i)
361 body_pointEigen.push_back(body_point[i]);
363 std::vector<RigidBodyDynamics::Math::Vector3d> markersInRbdl;
364 for (
unsigned int i = 0; i<markers.size(); ++i)
365 markersInRbdl.push_back(markers[i]);
368 std::vector<unsigned int> body_id;
369 for (
unsigned int i=0; i<body_point.size(); ++i)
370 body_id.push_back(
static_cast<unsigned int>((*(body_point.begin()+i)).parentId()) );
373 return RigidBodyDynamics::InverseKinematics(
375 Qinit, body_id, body_pointEigen, markersInRbdl, Q);
384 bool lookForTechnical)
392 std::vector<biorbd::utils::Matrix> G;
394 for (
unsigned int idx=0; idx<nbMarkers(); ++idx){
400 unsigned int id = model.GetBodyId(node.
parent().c_str());
405 RigidBodyDynamics::CalcPointJacobian(model, Q,
id, pos, G_tp,
false);
415 unsigned int nTechMarkers = 0;
416 if (nTechMarkers == 0)
417 for (
auto mark : *m_marks)
418 if (mark.isTechnical())
429 unsigned int nTechMarkers = 0;
434 if (nTechMarkers == 0)
435 for (
auto mark : *m_marks)
436 if (mark.isTechnical() && !mark.parent().compare(name))
445 unsigned int nAnatMarkers = 0;
446 if (nAnatMarkers == 0)
447 for (
auto mark : *m_marks)
448 if (mark.isAnatomical())
456 std::vector<biorbd::utils::String> names;
457 for (
unsigned int i=0; i<nbMarkers(); ++i)
458 names.push_back(marker(i).biorbd::utils::Node::name());
465 std::vector<biorbd::utils::String> names;
466 for (
unsigned int i=0; i<nbMarkers(); ++i)
467 if (marker(i).isTechnical())
468 names.push_back(marker(i).biorbd::utils::Node::name());
475 std::vector<biorbd::utils::String> names;
476 for (
unsigned int i=0; i<nbMarkers(); ++i)
477 if (marker(i).isAnatomical())
478 names.push_back(marker(i).biorbd::utils::Node::name());