50 virtual std::array<double, 16>
pose(
52 const std::array<double, 7>& q,
53 const std::array<double, 16>& F_T_EE,
54 const std::array<double, 16>& EE_T_K)
86 const std::array<double, 7>& q,
87 const std::array<double, 16>& F_T_EE,
88 const std::array<double, 16>& EE_T_K)
120 const std::array<double, 7>& q,
121 const std::array<double, 16>& F_T_EE,
122 const std::array<double, 16>& EE_T_K)
149 virtual std::array<double, 49>
mass(
150 const std::array<double, 7>& q,
151 const std::array<double, 9>& I_total,
153 const std::array<double, 3>& F_x_Ctotal)
184 virtual std::array<double, 7>
coriolis(
185 const std::array<double, 7>& q,
186 const std::array<double, 7>& dq,
187 const std::array<double, 9>& I_total,
189 const std::array<double, 3>& F_x_Ctotal)
204 const std::array<double, 7>& q,
206 const std::array<double, 3>& F_x_Ctotal
208 return gravity(q, m_total, F_x_Ctotal, {0, 0, -9.81});
223 virtual std::array<double, 7>
gravity(
224 const std::array<double, 7>& q,
226 const std::array<double, 3>& F_x_Ctotal,
227 const std::array<double, 3>& gravity_earth)
const = 0;
237 #ifdef ENABLE_BASE_ACCELERATION 253 const std::array<double, 3>& gravity_earth)
const {
std::array< double, 42 > zeroJacobian(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given joint relative to the base frame.
std::array< double, 16 > F_T_EE
std::array< double, 7 > gravity(const franka::RobotState &robot_state, const std::array< double, 3 > &gravity_earth) const
Calculates the gravity vector.
std::array< double, 7 > gravity(const franka::RobotState &robot_state) const
Calculates the gravity vector.
std::array< double, 3 > F_x_Ctotal
std::array< double, 7 > gravity(const std::array< double, 7 > &q, double m_total, const std::array< double, 3 > &F_x_Ctotal) const
Calculates the gravity vector.
Calculates poses of joints and dynamic properties of the robot.
virtual ~ModelBase() noexcept=default
std::array< double, 7 > q
std::array< double, 7 > dq
std::array< double, 9 > I_total
std::array< double, 42 > bodyJacobian(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 6x7 Jacobian for the given frame, relative to that frame.
std::array< double, 7 > coriolis(const franka::RobotState &robot_state) const
Calculates the Coriolis force vector (state-space equation): , in .
std::array< double, 16 > pose(franka::Frame frame, const franka::RobotState &robot_state) const
Gets the 4x4 pose matrix for the given frame in base frame.
std::array< double, 16 > EE_T_K
std::array< double, 49 > mass(const franka::RobotState &robot_state) const
Calculates the 7x7 mass matrix.