3#include <franka/model.h>
21 explicit Model(franka::Model model);
70 const Affine &EE_T_K)
const;
93 const Affine &EE_T_K)
const;
101 [[nodiscard]] Eigen::Matrix<double, 7, 7>
mass(
const RobotState &state)
const;
112 [[nodiscard]] Eigen::Matrix<double, 7, 7>
mass(
const Vector7d &q,
113 const Eigen::Matrix3d &I_total,
115 const Eigen::Vector3d &F_x_Ctotal)
const;
137 const Eigen::Matrix3d &I_total,
139 const Eigen::Vector3d &F_x_Ctotal)
const;
169 const Eigen::Vector3d &F_x_Ctotal,
170 const Eigen::Vector3d &gravity_earth = {0., 0., -9.81})
const;
173 franka::Model model_;
A wrapper around franka::Model that uses Eigen types.
Definition model.hpp:16
Affine pose(franka::Frame frame, const RobotState &state) const
Calculates the pose of a frame relative to the base frame.
Definition model.cpp:18
Model(const Model &)=delete
Jacobian bodyJacobian(franka::Frame frame, const RobotState &state) const
Calculates the body Jacobian in base frame.
Definition model.cpp:27
Eigen::Matrix< double, 7, 7 > mass(const RobotState &state) const
Calculates the mass matrix.
Definition model.cpp:45
Model & operator=(const Model &)=delete
Vector7d gravity(const RobotState &state, const Eigen::Vector3d &gravity_earth) const
Calculates the gravity vector.
Definition model.cpp:65
Vector7d coriolis(const RobotState &state) const
Calculates the Coriolis force vector.
Definition model.cpp:54
Jacobian zeroJacobian(franka::Frame frame, const RobotState &state) const
Calculates the zero Jacobian in base frame.
Definition model.cpp:36
Definition dynamics_limit.cpp:8
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:12
Eigen::Matrix< double, 6, 7 > Jacobian
Definition types.hpp:13
Eigen::Affine3d Affine
Definition types.hpp:16
Full state of the robot.
Definition robot_state.hpp:20