libfranka 0.18.0
FCI C++ API
Loading...
Searching...
No Matches
model.h
Go to the documentation of this file.
1// Copyright (c) 2023 Franka Robotics GmbH
2// Use of this source code is governed by the Apache-2.0 license, see LICENSE
3#pragma once
4
5#include <array>
6#include <memory>
7
8#include <franka/robot.h>
10#include <franka/robot_state.h>
11
17namespace franka {
18
22enum class Frame {
23 kJoint1,
24 kJoint2,
25 kJoint3,
26 kJoint4,
27 kJoint5,
28 kJoint6,
29 kJoint7,
30 kFlange,
31 kEndEffector,
32 kStiffness
33};
34
44Frame operator++(Frame& frame, int /* dummy */) noexcept;
45
49class Model {
50 public:
62 explicit Model(const std::string& urdf_model);
63
72 explicit Model(std::unique_ptr<RobotModelBase> robot_model);
73
79 Model(Model&& model) noexcept;
80
88 Model& operator=(Model&& model) noexcept;
89
93 ~Model() noexcept;
94
105 std::array<double, 16> pose(Frame frame, const franka::RobotState& robot_state) const;
106
119 std::array<double, 16> pose(
120 Frame frame,
121 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
122 const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
123 const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
124 const;
125
136 std::array<double, 42> bodyJacobian(Frame frame, const franka::RobotState& robot_state) const;
137
150 std::array<double, 42> bodyJacobian(
151 Frame frame,
152 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
153 const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
154 const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
155 const;
156
167 std::array<double, 42> zeroJacobian(Frame frame, const franka::RobotState& robot_state) const;
168
181 std::array<double, 42> zeroJacobian(
182 Frame frame,
183 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
184 const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
185 const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
186 const;
187
195 std::array<double, 49> mass(const franka::RobotState& robot_state) const noexcept;
196
210 std::array<double, 49> mass(
211 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
212 const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
213 double m_total,
214 const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
215 const noexcept;
216
225 std::array<double, 7> coriolis(const franka::RobotState& robot_state) const noexcept;
226
245 [[deprecated(
246 "Use coriolis(q, dq, i_total, m_total, f_x_ctotal, g_earth) instead")]] std::array<double, 7>
247 coriolis(const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
248 const std::array<double, 7>& dq, // NOLINT(readability-identifier-length)
249 const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
250 double m_total,
251 const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
252 const noexcept;
253
271 std::array<double, 7> coriolis(
272 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
273 const std::array<double, 7>& dq, // NOLINT(readability-identifier-length)
274 const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
275 double m_total,
276 const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
277 const std::array<double, 3>& gravity_earth) const noexcept;
278
292 std::array<double, 7> gravity(
293 const std::array<double, 7>& q, // NOLINT(readability-identifier-length)
294 double m_total,
295 const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
296 const std::array<double, 3>& gravity_earth = {{0., 0., -9.81}}) const noexcept;
297
306 std::array<double, 7> gravity(const franka::RobotState& robot_state,
307 const std::array<double, 3>& gravity_earth) const noexcept;
308
316 std::array<double, 7> gravity(const franka::RobotState& robot_state) const noexcept;
317
319 Model(const Model&) = delete;
320 Model& operator=(const Model&) = delete;
322
323 private:
324 std::unique_ptr<RobotModelBase> robot_model_;
325};
326
327} // namespace franka
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