62 explicit Model(
const std::string& urdf_model);
72 explicit Model(std::unique_ptr<RobotModelBase> robot_model);
121 const std::array<
double, 7>& q,
122 const std::array<
double, 16>& F_T_EE,
123 const std::array<
double, 16>& EE_T_K)
152 const std::array<
double, 7>& q,
153 const std::array<
double, 16>& F_T_EE,
154 const std::array<
double, 16>& EE_T_K)
183 const std::array<
double, 7>& q,
184 const std::array<
double, 16>& F_T_EE,
185 const std::array<
double, 16>& EE_T_K)
195 std::array<
double, 49>
mass(const franka::
RobotState& robot_state) const noexcept;
211 const std::array<
double, 7>& q,
212 const std::array<
double, 9>& I_total,
214 const std::array<
double, 3>& F_x_Ctotal)
246 "Use
coriolis(q, dq, i_total, m_total, f_x_ctotal, g_earth) instead")]] std::array<
double, 7>
248 const std::array<
double, 7>& dq,
249 const std::array<
double, 9>& I_total,
251 const std::array<
double, 3>& F_x_Ctotal)
272 const std::array<
double, 7>& q,
273 const std::array<
double, 7>& dq,
274 const std::array<
double, 9>& I_total,
276 const std::array<
double, 3>& F_x_Ctotal,
277 const std::array<
double, 3>& gravity_earth) const noexcept;
293 const std::array<
double, 7>& q,
295 const std::array<
double, 3>& F_x_Ctotal,
296 const std::array<
double, 3>& gravity_earth = {{0., 0., -9.81}})
const noexcept;
307 const std::array<double, 3>& gravity_earth)
const noexcept;
324 std::unique_ptr<RobotModelBase> robot_model_;
Calculates poses of joints and dynamic properties of the robot.
Definition model.h:49
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(const std::string &urdf_model)
Creates a new Model instance.
Model(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.
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.
Abstract interface class for robot dynamic parameters computed from the URDF model with Pinocchio.
Contains the franka::RobotState types.
Describes the robot state.
Definition robot_state.h:34