3#include <franka/model.h> 
   23  explicit Model(franka::Model model);
 
   99  [[nodiscard]] Eigen::Matrix<double, 7, 7> 
mass(
const RobotState &state) 
const;
 
  110  [[nodiscard]] Eigen::Matrix<double, 7, 7> 
mass(
 
  111      const Vector7d &q, 
const Eigen::Matrix3d &I_total, 
double m_total, 
const Eigen::Vector3d &F_x_Ctotal) 
const;
 
  132      const Vector7d &q, 
const Vector7d &dq, 
const Eigen::Matrix3d &I_total, 
double m_total,
 
  133      const Eigen::Vector3d &F_x_Ctotal) 
const;
 
  164      const Vector7d &q, 
double m_total, 
const Eigen::Vector3d &F_x_Ctotal,
 
  165      const Eigen::Vector3d &gravity_earth = {0., 0., -9.81}) 
const;
 
  168  franka::Model model_;
 
 
A wrapper around franka::Model that uses Eigen types.
Definition model.hpp:18
 
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:11
 
Eigen::Matrix< double, 6, 7 > Jacobian
Definition types.hpp:12
 
Eigen::Affine3d Affine
Definition types.hpp:15
 
Full state of the robot.
Definition robot_state.hpp:23