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

Robot model with integrated dynamics engine. More...

#include <Model.hpp>

Public Member Functions

 Model (const Robot &robot)
 [Non-blocking] Create a flexiv::Model instance and initialize the integrated dynamics engine. More...
 
void reload (void)
 [Blocking] Reload robot model 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 robot model using new joint states data. More...
 
const Eigen::MatrixXd getJacobian (const std::string &linkName)
 [Non-blocking] Compute and get the Jacobian matrix at the frame of the specified link \( i \), expressed in the base frame. More...
 
const Eigen::MatrixXd getJacobianDot (const std::string &linkName)
 [Non-blocking] Compute and get the time derivative of Jacobian matrix at the frame of the specified link \( i \), expressed in the base frame. More...
 
const Eigen::MatrixXd getMassMatrix ()
 [Non-blocking] Compute and get the mass matrix for the generalized coordinates, i.e. joint space. More...
 
const Eigen::MatrixXd getCoriolisMatrix ()
 [Non-blocking] Compute and get the Coriolis/centripetal matrix for the generalized coordinates, i.e. joint space. More...
 
const Eigen::VectorXd getGravityForce ()
 [Non-blocking] Compute and get the gravity force vector for the generalized coordinates, i.e. joint space. More...
 
const Eigen::VectorXd getCoriolisForce ()
 [Non-blocking] Compute and get the Coriolis force vector for the generalized coordinates, i.e. joint space. More...
 

Detailed Description

Robot model with integrated dynamics engine.

Examples
intermediate6_robot_dynamics.cpp.

Definition at line 21 of file Model.hpp.

Constructor & Destructor Documentation

◆ Model()

flexiv::Model::Model ( const Robot robot)

[Non-blocking] Create a flexiv::Model instance and initialize the integrated dynamics engine.

Parameters
[in]robotReference to the instance of flexiv::Robot.
Exceptions
InitExceptionif the instance failed to initialize.
Note
The robot mounting position set in Flexiv Elements is automatically synced over so that this dynamics engine produces the correct result.

Member Function Documentation

◆ getCoriolisForce()

const Eigen::VectorXd flexiv::Model::getCoriolisForce ( )

[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}^{DOF \times 1} \). Unit: \( [Nm] \).
Note
Call update() before this method.

◆ getCoriolisMatrix()

const Eigen::MatrixXd flexiv::Model::getCoriolisMatrix ( )

[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}^{DOF \times DOF} \).
Note
Call update() before this method.

◆ getGravityForce()

const Eigen::VectorXd flexiv::Model::getGravityForce ( )

[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}^{DOF \times 1} \). Unit: \( [Nm] \).
Note
Call update() before this method.
Examples
intermediate6_robot_dynamics.cpp.

◆ getJacobian()

const Eigen::MatrixXd flexiv::Model::getJacobian ( const std::string &  linkName)

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

Parameters
[in]linkNameName of the link to get Jacobian for.
Returns
Jacobian matrix: \( ^{0}J_i \in \mathbb{R}^{6 \times DOF} \).
Note
Call update() before this method.
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.
Exceptions
InputExceptionif the specified linkName does not exist.
Examples
intermediate6_robot_dynamics.cpp.

◆ getJacobianDot()

const Eigen::MatrixXd flexiv::Model::getJacobianDot ( const std::string &  linkName)

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

Parameters
[in]linkNameName of the link to get Jacobian derivative for.
Returns
Time derivative of Jacobian matrix: \( ^{0}\dot{J_i} \in \mathbb{R}^{6 \times DOF} \).
Note
Call update() before this method.
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.
Exceptions
InputExceptionif the specified linkName does not exist.

◆ getMassMatrix()

const Eigen::MatrixXd flexiv::Model::getMassMatrix ( )

[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}^{DOF \times DOF}_{++} \). Unit: \( [kgm^2] \).
Note
Call update() before this method.
Examples
intermediate6_robot_dynamics.cpp.

◆ reload()

void flexiv::Model::reload ( void  )

[Blocking] Reload robot model using the latest data synced from the connected robot. Tool model is also synced.

Exceptions
CommExceptionif failed to sync model data.
LogicExceptionif the synced robot model contains invalid data.
Note
Call this function if the robot tool has changed.
Warning
This function blocks until the model data is synced and the reloading is finished.

◆ update()

void flexiv::Model::update ( const std::vector< double > &  positions,
const std::vector< double > &  velocities 
)

[Non-blocking] Update robot model using new joint states data.

Parameters
[in]positionsCurrent joint positions: \( q \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad] \).
[in]velocitiesCurrent joint velocities: \( \dot{q} \in \mathbb{R}^{DOF \times 1} \). Unit: \( [rad/s] \).
Exceptions
InputExceptionif the input vector is of wrong size.
Examples
intermediate6_robot_dynamics.cpp.

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