Class RobotModel
Defined in File robot_model.h
Inheritance Relationships
Base Type
public RobotModelBase(Class RobotModelBase)
Class Documentation
-
class RobotModel : public RobotModelBase
Implements of RobotModelBase using Pinocchio.
Public Functions
-
RobotModel(const std::string &urdf)
-
virtual void coriolis(const std::array<double, 7> &q, const std::array<double, 7> &dq, const std::array<double, 9> &i_total, double m_total, const std::array<double, 3> &f_x_ctotal, std::array<double, 7> &c_ne) override
Calculates the Coriolis force vector (state-space equation): \( c= C \times dq\), in \([Nm]\).
- Parameters:
q – [in] Joint position.
dq – [in] Joint velocity.
i_total – [in] Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
m_total – [in] Weight of the attached total load including end effector. Unit: \([kg]\).
f_x_ctotal – [in] Translation from flange to center of mass of the attached total load. Unit: \([m]\).
c_ne – [out] Coriolis force vector. Unit: \([Nm]\).
-
virtual void coriolis(const std::array<double, 7> &q, const std::array<double, 7> &dq, const std::array<double, 9> &i_total, double m_total, const std::array<double, 3> &f_x_ctotal, const std::array<double, 3> &g_earth, std::array<double, 7> &c_ne) override
Calculates the Coriolis force vector with configurable gravity (recommended implementation). Unit: \([Nm]\).
- Parameters:
q – [in] Joint position.
dq – [in] Joint velocity.
i_total – [in] Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
m_total – [in] Weight of the attached total load including end effector. Unit: \([kg]\).
f_x_ctotal – [in] Translation from flange to center of mass of the attached total load. Unit: \([m]\).
g_earth – [in] Earth’s gravity vector. Unit: \(\frac{m}{s^2}\).
c_ne – [out] Coriolis force vector. Unit: \([Nm]\).
-
virtual void gravity(const std::array<double, 7> &q, const std::array<double, 3> &g_earth, double m_total, const std::array<double, 3> &f_x_ctotal, std::array<double, 7> &g_ne) override
Calculates the gravity vector. Unit: \([Nm]\).
- Parameters:
q – [in] Joint position.
gravity_earth – [in] Earth’s gravity vector. Unit: \(\frac{m}{s^2}\).
m_total – [in] Weight of the attached total load including end effector. Unit: \([kg]\).
f_x_Ctotal – [in] Translation from flange to center of mass of the attached total load.
g_ne – [out] Gravity vector. Unit: \([Nm]\).
-
virtual void mass(const std::array<double, 7> &q, const std::array<double, 9> &i_total, double m_total, const std::array<double, 3> &f_x_ctotal, std::array<double, 49> &m_ne) override
Calculates the 7x7 inertia matrix. Unit: \([kg \times m^2]\).
- Parameters:
q – [in] Joint position.
i_total – [in] Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: \([kg \times m^2]\).
m_total – [in] Weight of the attached total load including end effector. Unit: \([kg]\).
f_x_ctotal – [in] Translation from flange to center of mass of the attached total load. Unit: \([m]\).
m_ne – [out] Vectorized 7x7 inertia matrix, column-major.
-
virtual std::array<double, 16> pose(const std::array<double, 7> &q, int joint_index) override
Calculates the homogeneous transformation matrix for the specified joint or link.
- Parameters:
q – [in] Joint position.
joint_index – [in] The index of the joint/link for which to calculate the pose.
- Returns:
Homogeneous transformation matrix (4x4) in column-major order.
-
virtual std::array<double, 16> poseEe(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee) override
Calculates the homogeneous transformation matrix for the end effector, applying the end effector transformation.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
- Returns:
Homogeneous transformation matrix (4x4) in column-major order.
-
virtual std::array<double, 16> poseFlange(const std::array<double, 7> &q) override
Calculates the homogeneous transformation matrix for the flange.
- Parameters:
q – [in] Joint position.
- Returns:
Homogeneous transformation matrix (4x4) in column-major order.
-
virtual std::array<double, 16> poseStiffness(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee, const std::array<double, 16> &ee_t_k) override
Calculates the homogeneous transformation matrix for the stiffness frame.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
ee_t_k – [in] The transformation from end effector to stiffness frame (4x4 matrix, column-major).
- Returns:
Homogeneous transformation matrix (4x4) in column-major order.
-
virtual std::array<double, 42> bodyJacobian(const std::array<double, 7> &q, int joint_index) override
Calculates the 6x7 body Jacobian for the given joint, relative to that joint’s frame.
- Parameters:
q – [in] Joint position.
joint_index – [in] The index of the joint/link for which to calculate the Jacobian.
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> bodyJacobianFlange(const std::array<double, 7> &q) override
Calculates the 6x7 body Jacobian for the flange frame, relative to that frame.
- Parameters:
q – [in] Joint position.
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> bodyJacobianEe(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee) override
Calculates the 6x7 body Jacobian for the end effector frame, relative to that frame.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> bodyJacobianStiffness(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee, const std::array<double, 16> &ee_t_k) override
Calculates the 6x7 body Jacobian for the stiffness frame, relative to that frame.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
ee_t_k – [in] The transformation from end effector to stiffness frame (4x4 matrix, column-major).
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> zeroJacobian(const std::array<double, 7> &q, int joint_index) override
Calculates the 6x7 zero Jacobian for the given joint, relative to the base frame.
- Parameters:
q – [in] Joint position.
joint_index – [in] The index of the joint/link for which to calculate the Jacobian.
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> zeroJacobianFlange(const std::array<double, 7> &q) override
Calculates the 6x7 zero Jacobian for the flange frame, relative to the base frame.
- Parameters:
q – [in] Joint position.
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> zeroJacobianEe(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee) override
Calculates the 6x7 zero Jacobian for the end effector frame, relative to the base frame.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
virtual std::array<double, 42> zeroJacobianStiffness(const std::array<double, 7> &q, const std::array<double, 16> &f_t_ee, const std::array<double, 16> &ee_t_k) override
Calculates the 6x7 zero Jacobian for the stiffness frame, relative to the base frame.
- Parameters:
q – [in] Joint position.
f_t_ee – [in] The transformation from flange to end effector (4x4 matrix, column-major).
ee_t_k – [in] The transformation from end effector to stiffness frame (4x4 matrix, column-major).
- Returns:
Vectorized 6x7 Jacobian, column-major.
-
RobotModel(const std::string &urdf)