Flexiv RDK APIs  1.5
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 
60  void SyncURDF(const std::string& template_urdf_path);
61 
70  void Update(const std::vector<double>& positions, const std::vector<double>& velocities);
71 
83  const Eigen::MatrixXd J(const std::string& link_name);
84 
97  const Eigen::MatrixXd dJ(const std::string& link_name);
98 
106  const Eigen::MatrixXd M();
107 
114  const Eigen::MatrixXd C();
115 
122  const Eigen::VectorXd g();
123 
131  const Eigen::VectorXd c();
132 
145  const std::pair<bool, std::vector<double>> reachable(const std::array<double, kPoseSize>& pose,
146  const std::vector<double>& seed_positions, bool free_orientation);
147 
148 private:
149  class Impl;
150  std::unique_ptr<Impl> pimpl_;
151 };
152 
153 } /* namespace rdk */
154 } /* namespace flexiv */
155 
156 #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,...
void SyncURDF(const std::string &template_urdf_path)
[Blocking] Sync the actual kinematic parameters of the connected robot into the template URDF.
Main interface with the robot, containing several function categories and background services.
Definition: robot.hpp:25