Flexiv RDK APIs  1.4
model.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIV_RDK_MODEL_HPP_
7 #define FLEXIV_RDK_MODEL_HPP_
8 
9 #include "robot.hpp"
10 #include <Eigen/Eigen>
11 #include <memory>
12 
13 namespace flexiv {
14 namespace rdk {
15 
20 class Model
21 {
22 public:
32  Model(const Robot& robot,
33  const Eigen::Vector3d& gravity_vector = Eigen::Vector3d(0.0, 0.0, -9.81));
34  virtual ~Model();
35 
44  void Reload();
45 
54  void Update(const std::vector<double>& positions, const std::vector<double>& velocities);
55 
67  const Eigen::MatrixXd J(const std::string& link_name);
68 
81  const Eigen::MatrixXd dJ(const std::string& link_name);
82 
90  const Eigen::MatrixXd M();
91 
98  const Eigen::MatrixXd C();
99 
106  const Eigen::VectorXd g();
107 
115  const Eigen::VectorXd c();
116 
129  const std::pair<bool, std::vector<double>> reachable(const std::array<double, kPoseSize>& pose,
130  const std::vector<double>& seed_positions, bool free_orientation);
131 
132 private:
133  class Impl;
134  std::unique_ptr<Impl> pimpl_;
135 };
136 
137 } /* namespace rdk */
138 } /* namespace flexiv */
139 
140 #endif /* FLEXIV_RDK_MODEL_HPP_ */
Interface to access certain robot kinematics and dynamics data.
Definition: model.hpp:21
const Eigen::MatrixXd C()
[Non-blocking] Compute and get the Coriolis/centripetal matrix for the generalized coordinates,...
const Eigen::MatrixXd dJ(const std::string &link_name)
[Non-blocking] Compute and get the time derivative of Jacobian matrix at the frame of the specified l...
const Eigen::MatrixXd M()
[Non-blocking] Compute and get the mass matrix for the generalized coordinates, i....
Model(const Robot &robot, const Eigen::Vector3d &gravity_vector=Eigen::Vector3d(0.0, 0.0, -9.81))
[Non-blocking] Create an instance and initialize the integrated dynamics engine.
void Reload()
[Blocking] Reload robot model using the latest data synced from the connected robot....
const Eigen::MatrixXd J(const std::string &link_name)
[Non-blocking] Compute and get the Jacobian matrix at the frame of the specified link ,...
const Eigen::VectorXd g()
[Non-blocking] Compute and get the gravity force vector for the generalized coordinates,...
void Update(const std::vector< double > &positions, const std::vector< double > &velocities)
[Non-blocking] Update robot model using new joint states data.
const std::pair< bool, std::vector< double > > reachable(const std::array< double, kPoseSize > &pose, const std::vector< double > &seed_positions, bool free_orientation)
[Blocking] Check if a Cartesian pose is reachable. If yes, also return an IK solution of the correspo...
const Eigen::VectorXd c()
[Non-blocking] Compute and get the Coriolis force vector for the generalized coordinates,...
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:24