|  | Flexiv RDK APIs
    1.8.0
    | 
Interface to obtain certain model data of the robot, including kinematics and dynamics. More...
#include <model.hpp>
| Public Member Functions | |
| Model (const Robot &robot, const Eigen::Vector3d &gravity_vector=Eigen::Vector3d(0.0, 0.0, -9.81)) | |
| [Non-blocking] Instantiate the robot model interface.  More... | |
| std::vector< std::string > | link_names () const | 
| [Non-blocking] Names of all links in the robot model.  More... | |
| void | Reload () | 
| [Blocking] Reload (refresh) parameters of the robot model stored locally in this class using the latest data synced from the connected robot. Tool model is also synced.  More... | |
| 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 locally computed functions return results based on the updated configuration.  More... | |
| Eigen::MatrixXd | dJ (const std::string &link_name) | 
| [Non-blocking] Compute the time derivative of Jacobian matrix at the specified frame w.r.t. world frame.  More... | |
| Eigen::MatrixXd | M () | 
| [Non-blocking] Compute the mass matrix in generalized coordinates, i.e. joint space.  More... | |
| Eigen::MatrixXd | C () | 
| [Non-blocking] Compute the Coriolis/centripetal matrix in generalized coordinates, i.e. joint space.  More... | |
| Eigen::VectorXd | g () | 
| [Non-blocking] Compute the gravity force vector in generalized coordinates, i.e. joint space.  More... | |
| Eigen::VectorXd | c () | 
| [Non-blocking] Compute the Coriolis force vector in generalized coordinates, i.e. joint space.  More... | |
| Eigen::MatrixXd | J (const std::string &link_name) | 
| [Non-blocking] Compute the Jacobian matrix at the specified frame w.r.t. world frame.  More... | |
| Eigen::Isometry3d | T (const std::string &link_name) | 
| [Non-blocking] Compute the transformation matrix of the specified frame w.r.t. world frame.  More... | |
| void | SyncURDF (const std::string &template_urdf_path) | 
| [Blocking] Sync the actual kinematic parameters of the connected robot into the template URDF.  More... | |
| 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 corresponding joint positions.  More... | |
| std::pair< double, double > | configuration_score () const | 
| [Blocking] Score of the robot's current configuration (posture), calculated from the manipulability measurements.  More... | |
Interface to obtain certain model data of the robot, including kinematics and dynamics.
| flexiv::rdk::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.
| [in] | robot | Reference to the instance of flexiv::rdk::Robot. | 
| [in] | gravity_vector | Earth's gravity vector in world frame. Default to \( [0.0, 0.0, -9.81]^T \). Unit: \( [m/s^2] \). | 
| std::runtime_error | if the initialization sequence failed. | 
| std::logic_error | if the connected robot does not have an RDK professional license; or the parsed robot model is not supported. | 
| Eigen::MatrixXd flexiv::rdk::Model::C | ( | ) | 
[Non-blocking] Compute the Coriolis/centripetal matrix in generalized coordinates, i.e. joint space.
| Eigen::VectorXd flexiv::rdk::Model::c | ( | ) | 
[Non-blocking] Compute the Coriolis force vector in generalized coordinates, i.e. joint space.
| std::pair<double, double> flexiv::rdk::Model::configuration_score | ( | ) | const | 
[Blocking] Score of the robot's current configuration (posture), calculated from the manipulability measurements.
| std::runtime_error | if failed to get a reply from the connected robot. | 
| Eigen::MatrixXd flexiv::rdk::Model::dJ | ( | const std::string & | link_name | ) | 
[Non-blocking] Compute the time derivative of Jacobian matrix at the specified frame w.r.t. world frame.
| [in] | link_name | Name of the link whose frame is the specified one. | 
| std::invalid_argument | if [link_name] does not exist. | 
| Eigen::VectorXd flexiv::rdk::Model::g | ( | ) | 
[Non-blocking] Compute the gravity force vector in generalized coordinates, i.e. joint space.
| Eigen::MatrixXd flexiv::rdk::Model::J | ( | const std::string & | link_name | ) | 
[Non-blocking] Compute the Jacobian matrix at the specified frame w.r.t. world frame.
| [in] | link_name | Name of the link whose frame is the specified one. | 
| std::invalid_argument | if [link_name] does not exist. | 
| std::vector<std::string> flexiv::rdk::Model::link_names | ( | ) | const | 
[Non-blocking] Names of all links in the robot model.
| Eigen::MatrixXd flexiv::rdk::Model::M | ( | ) | 
[Non-blocking] Compute the mass matrix in generalized coordinates, i.e. joint space.
| std::pair<bool, std::vector<double> > flexiv::rdk::Model::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 corresponding joint positions.
| [in] | pose | Cartesian pose to be checked. | 
| [in] | seed_positions | Joint positions to be used as the seed for solving IK. | 
| [in] | free_orientation | Only constrain position and allow orientation to move freely. | 
| std::invalid_argument | if size of [seed_positions] does not match robot DoF. | 
| std::runtime_error | if failed to get a reply from the connected robot. | 
| void flexiv::rdk::Model::Reload | ( | ) | 
[Blocking] Reload (refresh) parameters of the robot model stored locally in this class using the latest data synced from the connected robot. Tool model is also synced.
| std::runtime_error | if failed to sync model data. | 
| std::logic_error | if the synced robot model contains invalid data. | 
| void flexiv::rdk::Model::SyncURDF | ( | const std::string & | template_urdf_path | ) | 
[Blocking] Sync the actual kinematic parameters of the connected robot into the template URDF.
| [in] | template_urdf_path | Path to the template URDF in [flexiv_rdk/resources] directory. This template URDF will be updated when the sync is finished. | 
| std::invalid_argument | if failed to load the template URDF. | 
| std::runtime_error | if failed to sync the URDF. | 
| Eigen::Isometry3d flexiv::rdk::Model::T | ( | const std::string & | link_name | ) | 
[Non-blocking] Compute the transformation matrix of the specified frame w.r.t. world frame.
| [in] | link_name | Name of the link whose frame is the specified one. | 
| std::invalid_argument | if [link_name] does not exist. | 
| void flexiv::rdk::Model::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 locally computed functions return results based on the updated configuration.
| [in] | positions | Current joint positions: \( q \in \mathbb{R}^{n \times 1} \). Unit: \( [rad] \). | 
| [in] | velocities | Current joint velocities: \( \dot{q} \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s] \). | 
| std::invalid_argument | if size of any input vector does not match robot DoF. |