Class FrankaRobotModel

Inheritance Relationships

Base Type

  • public semantic_components::SemanticComponentInterface< franka_hardware::Model >

Class Documentation

class FrankaRobotModel : public semantic_components::SemanticComponentInterface<franka_hardware::Model>

Public Functions

FrankaRobotModel(const std::string &franka_model_interface_name, const std::string &franka_state_interface_name)

Creates an instance of a FrankaRobotModel.

Parameters:

name[in] The name of robot model state interface.

FrankaRobotModel() = delete
virtual ~FrankaRobotModel() = default
inline std::array<double, 49> getMassMatrix()

Calculates the 7x7 mass matrix from the current robot state. Unit: [kg×m2].

See also

franka::Model::mass

Throws:

Runtime – error when state interfaces are not available.

Returns:

Vectorized 7x7 mass matrix, column-major.

inline std::array<double, 7> getCoriolisForceVector()

Calculates the Coriolis force vector (state-space equation) from the current robot state: c=C×dq, in [Nm].

See also

franka::Model::coriolis

Throws:

Runtime – error when state interfaces are not available.

Returns:

Coriolis force vector.

inline std::array<double, 7> getGravityForceVector()

Calculates the gravity vector from the current robot state. Unit: [Nm].

See also

franka::Model::gravity

Throws:

Runtime – error when state interfaces are not available

Returns:

Gravity vector.

inline std::array<double, 16> getPoseMatrix(const franka::Frame &frame)

Gets the 4x4 pose matrix for the given frame in base frame, calculated from the current robot state.

The pose is represented as a 4x4 matrix in column-major format.

See also

franka::Model::pose

Parameters:

frame[in] The desired frame.

Throws:

Runtime – error when state interfaces are not available

Returns:

Vectorized 4x4 pose matrix, column-major.

inline std::array<double, 42> getBodyJacobian(const franka::Frame &frame)

Gets the 6x7 Jacobian for the given frame, relative to the given frame.

BodyJacobian relates joint velocities to the end-effoctor twist expressed in the the given frame.

The Jacobian is represented as a 6x7 matrix in column-major format and calculated from the current robot state.

Jacobian matrix is in the form | linear components | | angular components |

E.g.

To calculate the Jacobian of frame kJoint1 w.r.t kJoint1

getBodyJacobian: (frame = kJoint1) will return kJoint1_J_kJoint1(6x7)

kJoint1_J_kJoint1 can be used to calculate the twist in the Joint1 by multiplying with the joint velocities.

1V1=1J1dq

Similarly, given desired joint twist in the kJoint1 frame, pseudoinverse of body jacobian can be used to retrieve the desired joint velocity to command.

dq= 1J11V1

See also

franka::Model::bodyJacobian

Parameters:

frame[in] The desired frame.

Throws:

Runtime – error when state interfaces are not available.

Returns:

Vectorized 6x7 Jacobian, column-major.

inline std::array<double, 42> getZeroJacobian(const franka::Frame &frame)

Gets the 6x7 Jacobian for the given joint relative to the base(zero) frame.

The Jacobian is represented as a 6x7 matrix in column-major format and calculated from the current robot state.

Jacobian matrix is in the form | linear components | | angular components |

E.g.

To calculate the Jacobian of frame kJoint1 w.r.t base frame

getZeroJacobian: (frame: kJoint1) will return base_J_kJoint1(6x7)

base_J_kJoint1 can be used to calculate the twist in the Joint1 by multiplying with the joint velocities.

OV1=OJ1dq

Similarly, given desired joint twist in the base frame, pseudoinverse of zero jacobian can be used to retrieve the desired joint velocity to command.

dq=OJ1OV1

See also

franka::Model::zeroJacobian

Parameters:

frame[in] The desired frame.

Throws:

Runtime – error when state interfaces are not available.

Returns:

Vectorized 6x7 Jacobian, column-major.

Protected Functions

void initialize()

Retrieve the robot state and robot model pointers from the hardware state interface

Throws:

Runtime – error when state interfaces are not available.