Flexiv RDK APIs  1.7.0
Public Member Functions | List of all members
flexiv::rdk::Model Class Reference

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...
 
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 dynamics functions return results based on the updated configuration. More...
 
Eigen::MatrixXd J (const std::string &link_name)
 [Non-blocking] Compute and get the Jacobian matrix at the frame of the specified link \( i \), expressed in world frame. More...
 
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 link \( i \), expressed in world frame. More...
 
Eigen::MatrixXd M ()
 [Non-blocking] Compute and get the mass matrix for the generalized coordinates, i.e. joint space. More...
 
Eigen::MatrixXd C ()
 [Non-blocking] Compute and get the Coriolis/centripetal matrix for the generalized coordinates, i.e. joint space. More...
 
Eigen::VectorXd g ()
 [Non-blocking] Compute and get the gravity force vector for the generalized coordinates, i.e. joint space. More...
 
Eigen::VectorXd c ()
 [Non-blocking] Compute and get the Coriolis force vector for the generalized coordinates, i.e. joint space. 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...
 

Detailed Description

Interface to obtain certain model data of the robot, including kinematics and dynamics.

Definition at line 20 of file model.hpp.

Constructor & Destructor Documentation

◆ Model()

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.

Parameters
[in]robotReference to the instance of flexiv::rdk::Robot.
[in]gravity_vectorEarth's gravity vector in world frame. Default to \( [0.0, 0.0, -9.81]^T \). Unit: \( [m/s^2] \).
Exceptions
std::runtime_errorif the initialization sequence failed.
std::logic_errorif the connected robot does not have an RDK professional license; or the parsed robot model is not supported.

Member Function Documentation

◆ C()

Eigen::MatrixXd flexiv::rdk::Model::C ( )

[Non-blocking] Compute and get the Coriolis/centripetal matrix for the generalized coordinates, i.e. joint space.

Returns
Coriolis/centripetal matrix: \( C(q,\dot{q}) \in \mathbb{R}^{n \times n} \).
Note
Call Update() before this function.

◆ c()

Eigen::VectorXd flexiv::rdk::Model::c ( )

[Non-blocking] Compute and get the Coriolis force vector for the generalized coordinates, i.e. joint space.

Returns
Coriolis force vector: \( c(q,\dot{q}) \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm] \).
Note
Call Update() before this function.

◆ configuration_score()

std::pair<double, double> flexiv::rdk::Model::configuration_score ( ) const

[Blocking] Score of the robot's current configuration (posture), calculated from the manipulability measurements.

Returns
A pair of {translation_score, orientation_score}. The quality of configuration based on score is mapped as: poor = [0, 20), medium = [20, 40), good = [40, 100].
Exceptions
std::runtime_errorif failed to get a reply from the connected robot.
Note
This function blocks until a reply is received.
Warning
A poor configuration score means the robot is near or at singularity, which can lead to degraded Cartesian performance. Use configuration with high scores for better manipulability and task results.

◆ dJ()

Eigen::MatrixXd flexiv::rdk::Model::dJ ( const std::string &  link_name)

[Non-blocking] Compute and get the time derivative of Jacobian matrix at the frame of the specified link \( i \), expressed in world frame.

Parameters
[in]link_nameName of the link to get Jacobian derivative for.
Returns
Time derivative of the Jacobian matrix: \( ^{0}\dot{J_i} \in \mathbb{R}^{m \times n} \).
Exceptions
std::out_of_rangeif the specified link_name does not exist.
Note
Call Update() before this function.
Available links can be found in the provided URDF. They are {"base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "flange"}, plus "tool" if any flange tool is mounted.

◆ g()

Eigen::VectorXd flexiv::rdk::Model::g ( )

[Non-blocking] Compute and get the gravity force vector for the generalized coordinates, i.e. joint space.

Returns
Gravity force vector: \( g(q) \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm] \).
Note
Call Update() before this function.

◆ J()

Eigen::MatrixXd flexiv::rdk::Model::J ( const std::string &  link_name)

[Non-blocking] Compute and get the Jacobian matrix at the frame of the specified link \( i \), expressed in world frame.

Parameters
[in]link_nameName of the link to get Jacobian for.
Returns
Jacobian matrix: \( ^{0}J_i \in \mathbb{R}^{m \times n} \).
Exceptions
std::out_of_rangeif the specified link_name does not exist.
Note
Call Update() before this function.
Available links can be found in the provided URDF. They are {"base_link", "link1", "link2", "link3", "link4", "link5", "link6", "link7", "flange"}, plus "tool" if any flange tool is mounted.

◆ M()

Eigen::MatrixXd flexiv::rdk::Model::M ( )

[Non-blocking] Compute and get the mass matrix for the generalized coordinates, i.e. joint space.

Returns
Symmetric positive definite mass matrix: \( M(q) \in \mathbb{S}^{n \times n}_{++} \). Unit: \( [kgm^2] \).
Note
Call Update() before this function.

◆ reachable()

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.

Parameters
[in]poseCartesian pose to be checked.
[in]seed_positionsJoint positions to be used as the seed for solving IK.
[in]free_orientationOnly constrain position and allow orientation to move freely.
Returns
A pair of {is_reachable, ik_solution}.
Exceptions
std::invalid_argumentif size of [seed_positions] does not match robot DoF.
std::runtime_errorif failed to get a reply from the connected robot.
Note
This function blocks until a reply is received.

◆ Reload()

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.

Exceptions
std::runtime_errorif failed to sync model data.
std::logic_errorif the synced robot model contains invalid data.
Note
This function blocks until the model parameters are synced and reloaded.
This function does not affect the kinematics functions.
Warning
Parameters of the locally-stored robot model must be manually refreshed using this function whenever a physical change is made to the connected robot (e.g. a tool is added or changed). Otherwise all dynamics functions will return incorrect results.

◆ SyncURDF()

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.

Parameters
[in]template_urdf_pathPath to the template URDF in [flexiv_rdk/resources] directory. This template URDF will be updated when the sync is finished.
Exceptions
std::invalid_argumentif failed to load the template URDF.
std::runtime_errorif failed to sync the URDF.
Note
This function blocks until the URDF syncing is finished.
Why is this function needed?
The URDFs in [flexiv_rdk/resources] directory contain kinematic parameters of the latest robot hardware version, which might be different from older versions. This function is therefore provided to sync the actual kinematic parameters of the connected robot into the template URDF.

◆ Update()

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 dynamics functions return results based on the updated configuration.

Parameters
[in]positionsCurrent joint positions: \( q \in \mathbb{R}^{n \times 1} \). Unit: \( [rad] \).
[in]velocitiesCurrent joint velocities: \( \dot{q} \in \mathbb{R}^{n \times 1} \). Unit: \( [rad/s] \).
Exceptions
std::invalid_argumentif size of any input vector does not match robot DoF.
Note
This function does not affect the kinematics functions.

The documentation for this class was generated from the following file: