Flexiv RDK APIs  0.10
Model.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIVRDK_MODEL_HPP_
7 #define FLEXIVRDK_MODEL_HPP_
8 
9 #include "Robot.hpp"
10 
11 #include <Eigen/Eigen>
12 #include <memory>
13 #include <vector>
14 
15 namespace flexiv {
16 
21 class Model
22 {
23 public:
32  Model(const Robot& robot);
33  virtual ~Model();
34 
44  void reload(void);
45 
54  void update(const std::vector<double>& positions,
55  const std::vector<double>& velocities);
56 
68  const Eigen::MatrixXd getJacobian(const std::string& linkName);
69 
83  const Eigen::MatrixXd getJacobianDot(const std::string& linkName);
84 
92  const Eigen::MatrixXd getMassMatrix();
93 
101  const Eigen::MatrixXd getCoriolisMatrix();
102 
110  const Eigen::VectorXd getGravityForce();
111 
119  const Eigen::VectorXd getCoriolisForce();
120 
121 private:
122  class Impl;
123  std::unique_ptr<Impl> m_pimpl;
124 };
125 
126 } /* namespace flexiv */
127 
128 #endif /* FLEXIVRDK_MODEL_HPP_ */
Robot model with integrated dynamics engine.
Definition: Model.hpp:22
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.
Definition: Robot.hpp:25