6 #ifndef FLEXIV_RDK_MODEL_HPP_ 
    7 #define FLEXIV_RDK_MODEL_HPP_ 
   10 #include <Eigen/Eigen> 
   33         const Eigen::Vector3d& gravity_vector = Eigen::Vector3d(0.0, 0.0, -9.81));
 
   64     void Update(
const std::vector<double>& positions, 
const std::vector<double>& velocities);
 
   79     Eigen::MatrixXd 
dJ(
const std::string& link_name);
 
  125     Eigen::MatrixXd 
J(
const std::string& link_name);
 
  138     Eigen::Isometry3d 
T(
const std::string& link_name);
 
  154     void SyncURDF(
const std::string& template_urdf_path);
 
  167     std::pair<bool, std::vector<double>> 
reachable(
const std::array<double, kPoseSize>& pose,
 
  168         const std::vector<double>& seed_positions, 
bool free_orientation) 
const;
 
  185     std::unique_ptr<Impl> pimpl_;
 
Interface to obtain certain model data of the robot, including kinematics and dynamics.
 
Eigen::MatrixXd J(const std::string &link_name)
[Non-blocking] Compute the Jacobian matrix at the specified frame w.r.t. world frame.
 
std::vector< std::string > link_names() const
[Non-blocking] Names of all links in the robot model.
 
Model(const Robot &robot, const Eigen::Vector3d &gravity_vector=Eigen::Vector3d(0.0, 0.0, -9.81))
[Non-blocking] Instantiate the robot model interface.
 
Eigen::VectorXd c()
[Non-blocking] Compute the Coriolis force vector in generalized coordinates, i.e. joint space.
 
Eigen::MatrixXd dJ(const std::string &link_name)
[Non-blocking] Compute the time derivative of Jacobian matrix at the specified frame w....
 
void Reload()
[Blocking] Reload (refresh) parameters of the robot model stored locally in this class using the late...
 
std::pair< bool, std::vector< double > > reachable(const std::array< double, kPoseSize > &pose, const std::vector< double > &seed_positions, bool free_orientation) const
[Blocking] Check if a Cartesian pose is reachable. If yes, also return an IK solution of the correspo...
 
Eigen::Isometry3d T(const std::string &link_name)
[Non-blocking] Compute the transformation matrix of the specified frame w.r.t. world frame.
 
void Update(const std::vector< double > &positions, const std::vector< double > &velocities)
[Non-blocking] Update the configuration (posture) of the locally-stored robot model so that the local...
 
std::pair< double, double > configuration_score() const
[Blocking] Score of the robot's current configuration (posture), calculated from the manipulability m...
 
Eigen::VectorXd g()
[Non-blocking] Compute the gravity force vector in generalized coordinates, i.e. joint space.
 
Eigen::MatrixXd M()
[Non-blocking] Compute the mass matrix in generalized coordinates, i.e. joint space.
 
void SyncURDF(const std::string &template_urdf_path)
[Blocking] Sync the actual kinematic parameters of the connected robot into the template URDF.
 
Eigen::MatrixXd C()
[Non-blocking] Compute the Coriolis/centripetal matrix in generalized coordinates,...
 
Main interface to control the robot, containing several function categories and background services.