9#include <franka/robot_model_base.h> 
   65  explicit Model(franka::Network& network, 
const std::string& urdf_model);
 
   76  explicit Model(franka::Network& network, std::unique_ptr<RobotModelBase> robot_model);
 
  125      const std::array<
double, 7>& q,
 
  126      const std::array<
double, 16>& F_T_EE,  
 
  127      const std::array<
double, 16>& EE_T_K)  
 
  156      const std::array<
double, 7>& q,
 
  157      const std::array<
double, 16>& F_T_EE,  
 
  158      const std::array<
double, 16>& EE_T_K)  
 
  187      const std::array<
double, 7>& q,
 
  188      const std::array<
double, 16>& F_T_EE,  
 
  189      const std::array<
double, 16>& EE_T_K)  
 
  199  std::array<
double, 49> 
mass(const franka::
RobotState& robot_state) const noexcept;
 
  215      const std::array<
double, 7>& q,
 
  216      const std::array<
double, 9>& I_total,  
 
  218      const std::array<
double, 3>& F_x_Ctotal)  
 
  250      "Use 
coriolis(q, dq, i_total, m_total, f_x_ctotal, g_earth) instead")]] std::array<
double, 7>
 
  252           const std::array<
double, 7>& dq,
 
  253           const std::array<
double, 9>& I_total,  
 
  255           const std::array<
double, 3>& F_x_Ctotal)  
 
  276      const std::array<
double, 7>& q,
 
  277      const std::array<
double, 7>& dq,
 
  278      const std::array<
double, 9>& I_total,  
 
  280      const std::array<
double, 3>& F_x_Ctotal,  
 
  281      const std::array<
double, 3>& gravity_earth) const noexcept;
 
  297      const std::array<
double, 7>& q,
 
  299      const std::array<
double, 3>& F_x_Ctotal,  
 
  300      const std::array<
double, 3>& gravity_earth = {{0., 0., -9.81}}) 
const noexcept;
 
  311                                const std::array<double, 3>& gravity_earth) 
const noexcept;
 
  328  std::unique_ptr<ModelLibrary> library_;
 
  329  std::unique_ptr<RobotModelBase> robot_model_;
 
 
Calculates poses of joints and dynamic properties of the robot.
Definition model.h:52
 
std::array< double, 42 > zeroJacobian(Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
 
~Model() noexcept
Unloads the model library.
 
std::array< double, 7 > gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const noexcept
Calculates the gravity vector.
 
std::array< double, 49 > mass(const franka::RobotState &robot_state) const noexcept
Calculates the 7x7 mass matrix.
 
Model(franka::Network &network, std::unique_ptr< RobotModelBase > robot_model)
Creates a new Model instance only for the tests.
 
Model(Model &&model) noexcept
Move-constructs a new Model instance.
 
Model(franka::Network &network, const std::string &urdf_model)
Creates a new Model instance.
 
std::array< double, 7 > coriolis(const franka::RobotState &robot_state) const noexcept
Calculates the Coriolis force vector (state-space equation): , in .
 
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal, const std::array< double, 3 > &gravity_earth={{0., 0., -9.81}}) const noexcept
Calculates the gravity vector.
 
std::array< double, 16 > pose(Frame frame, const franka::RobotState &robot_state) const
Gets the 4x4 pose matrix for the given frame in base frame.
 
std::array< double, 7 > gravity(const franka::RobotState &robot_state) const noexcept
Calculates the gravity vector using the robot state.
 
Model & operator=(Model &&model) noexcept
Move-assigns this Model from another Model instance.
 
std::array< double, 42 > bodyJacobian(Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given frame, relative to that frame.
 
Frame
Enumerates the seven joints, the flange, and the end effector of a robot.
Definition model.h:22
 
Frame operator++(Frame &frame, int) noexcept
Post-increments the given Frame by one.
 
Contains the franka::Robot type.
 
Contains the franka::RobotState types.
 
Describes the robot state.
Definition robot_state.h:34