6 #ifndef FLEXIVRDK_MODEL_HPP_
7 #define FLEXIVRDK_MODEL_HPP_
11 #include <Eigen/Eigen>
54 void update(
const std::vector<double>& positions,
55 const std::vector<double>& velocities);
68 const Eigen::MatrixXd
getJacobian(
const std::string& linkName);
123 std::unique_ptr<Impl> m_pimpl;
Robot model with integrated dynamics engine.
void update(const std::vector< double > &positions, const std::vector< double > &velocities)
[Non-blocking] Update robot model using new joint states data.
Model(const Robot &robot)
[Non-blocking] Create a flexiv::Model instance and initialize the integrated dynamics engine.
const Eigen::MatrixXd getMassMatrix()
[Non-blocking] Compute and get the mass matrix for the generalized coordinates, i....
const Eigen::MatrixXd getJacobian(const std::string &linkName)
[Non-blocking] Compute and get the Jacobian matrix at the frame of the specified link ,...
const Eigen::MatrixXd getCoriolisMatrix()
[Non-blocking] Compute and get the Coriolis/centripetal matrix for the generalized coordinates,...
const Eigen::VectorXd getCoriolisForce()
[Non-blocking] Compute and get the Coriolis force vector for the generalized coordinates,...
const Eigen::MatrixXd getJacobianDot(const std::string &linkName)
[Non-blocking] Compute and get the time derivative of Jacobian matrix at the frame of the specified l...
void reload(void)
[Blocking] Reload robot model using the latest data synced from the connected robot....
const Eigen::VectorXd getGravityForce()
[Non-blocking] Compute and get the gravity force vector for the generalized coordinates,...
Main interface with the robot, containing several function categories and background services.