forked from frankaemika/libfranka
-
Notifications
You must be signed in to change notification settings - Fork 0
/
model.h
283 lines (257 loc) · 8.78 KB
/
model.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
// Copyright (c) 2017 Franka Emika GmbH
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
#pragma once
#include <array>
#include <memory>
#include <franka/robot.h>
#include <franka/robot_state.h>
/**
* @file model.h
* Contains model library types.
*/
namespace franka {
/**
* Enumerates the seven joints, the flange, and the end effector of a robot.
*/
enum class Frame {
kJoint1,
kJoint2,
kJoint3,
kJoint4,
kJoint5,
kJoint6,
kJoint7,
kFlange,
kEndEffector,
kStiffness
};
/**
* Post-increments the given Frame by one.
*
* For example, Frame::kJoint2++ results in Frame::kJoint3.
*
* @param[in] frame Frame to increment.
*
* @return Original Frame.
*/
Frame operator++(Frame& frame, int /* dummy */) noexcept;
class ModelLibrary;
class Network;
/**
* Calculates poses of joints and dynamic properties of the robot.
*/
class Model {
public:
/**
* Creates a new Model instance.
*
* This constructor is for internal use only.
*
* @see Robot::loadModel
*
* @param[in] network For internal use.
*
* @throw ModelException if the model library cannot be loaded.
*/
explicit Model(franka::Network& network);
/**
* Move-constructs a new Model instance.
*
* @param[in] model Other Model instance.
*/
Model(Model&& model) noexcept;
/**
* Move-assigns this Model from another Model instance.
*
* @param[in] model Other Model instance.
*
* @return Model instance.
*/
Model& operator=(Model&& model) noexcept;
/**
* Unloads the model library.
*/
~Model() noexcept;
/**
* Gets the 4x4 pose matrix for the given frame in base frame.
*
* The pose is represented as a 4x4 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] robot_state State from which the pose should be calculated.
*
* @return Vectorized 4x4 pose matrix, column-major.
*/
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.
*
* The pose is represented as a 4x4 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] q Joint position.
* @param[in] F_T_EE End effector in flange frame.
* @param[in] EE_T_K Stiffness frame K in the end effector frame.
*
* @return Vectorized 4x4 pose matrix, column-major.
*/
std::array<double, 16> pose(
Frame frame,
const std::array<double, 7>& q,
const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
const;
/**
* Gets the 6x7 Jacobian for the given frame, relative to that frame.
*
* The Jacobian is represented as a 6x7 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] robot_state State from which the pose should be calculated.
*
* @return Vectorized 6x7 Jacobian, column-major.
*/
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.
*
* The Jacobian is represented as a 6x7 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] q Joint position.
* @param[in] F_T_EE End effector in flange frame.
* @param[in] EE_T_K Stiffness frame K in the end effector frame.
*
* @return Vectorized 6x7 Jacobian, column-major.
*/
std::array<double, 42> bodyJacobian(
Frame frame,
const std::array<double, 7>& q,
const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
const;
/**
* Gets the 6x7 Jacobian for the given joint relative to the base frame.
*
* The Jacobian is represented as a 6x7 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] robot_state State from which the pose should be calculated.
*
* @return Vectorized 6x7 Jacobian, column-major.
*/
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.
*
* The Jacobian is represented as a 6x7 matrix in column-major format.
*
* @param[in] frame The desired frame.
* @param[in] q Joint position.
* @param[in] F_T_EE End effector in flange frame.
* @param[in] EE_T_K Stiffness frame K in the end effector frame.
*
* @return Vectorized 6x7 Jacobian, column-major.
*/
std::array<double, 42> zeroJacobian(
Frame frame,
const std::array<double, 7>& q,
const std::array<double, 16>& F_T_EE, // NOLINT(readability-identifier-naming)
const std::array<double, 16>& EE_T_K) // NOLINT(readability-identifier-naming)
const;
/**
* Calculates the 7x7 mass matrix. Unit: \f$[kg \times m^2]\f$.
*
* @param[in] robot_state State from which the pose should be calculated.
*
* @return Vectorized 7x7 mass matrix, column-major.
*/
std::array<double, 49> mass(const franka::RobotState& robot_state) const noexcept;
/**
* Calculates the 7x7 mass matrix. Unit: \f$[kg \times m^2]\f$.
*
* @param[in] q Joint position.
* @param[in] I_total Inertia of the attached total load including end effector, relative to
* center of mass, given as vectorized 3x3 column-major matrix. Unit: \f$[kg \times m^2]\f$.
* @param[in] m_total Weight of the attached total load including end effector.
* Unit: \f$[kg]\f$.
* @param[in] F_x_Ctotal Translation from flange to center of mass of the attached total load.
* Unit: \f$[m]\f$.
*
* @return Vectorized 7x7 mass matrix, column-major.
*/
std::array<double, 49> mass(
const std::array<double, 7>& q,
const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
double m_total,
const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
const noexcept;
/**
* Calculates the Coriolis force vector (state-space equation): \f$ c= C \times
* dq\f$, in \f$[Nm]\f$.
*
* @param[in] robot_state State from which the Coriolis force vector should be calculated.
*
* @return Coriolis force vector.
*/
std::array<double, 7> coriolis(const franka::RobotState& robot_state) const noexcept;
/**
* Calculates the Coriolis force vector (state-space equation): \f$ c= C \times
* dq\f$, in \f$[Nm]\f$.
*
* @param[in] q Joint position.
* @param[in] dq Joint velocity.
* @param[in] I_total Inertia of the attached total load including end effector, relative to
* center of mass, given as vectorized 3x3 column-major matrix. Unit: \f$[kg \times m^2]\f$.
* @param[in] m_total Weight of the attached total load including end effector.
* Unit: \f$[kg]\f$.
* @param[in] F_x_Ctotal Translation from flange to center of mass of the attached total load.
* Unit: \f$[m]\f$.
*
* @return Coriolis force vector.
*/
std::array<double, 7> coriolis(
const std::array<double, 7>& q,
const std::array<double, 7>& dq,
const std::array<double, 9>& I_total, // NOLINT(readability-identifier-naming)
double m_total,
const std::array<double, 3>& F_x_Ctotal) // NOLINT(readability-identifier-naming)
const noexcept;
/**
* Calculates the gravity vector. Unit: \f$[Nm]\f$.
*
* @param[in] q Joint position.
* @param[in] m_total Weight of the attached total load including end effector.
* Unit: \f$[kg]\f$.
* @param[in] F_x_Ctotal Translation from flange to center of mass of the attached total load.
* Unit: \f$[m]\f$.
* @param[in] gravity_earth Earth's gravity vector. Unit: \f$\frac{m}{s^2}\f$.
* Default to {0.0, 0.0, -9.81}.
*
* @return Gravity vector.
*/
std::array<double, 7> gravity(
const std::array<double, 7>& q,
double m_total,
const std::array<double, 3>& F_x_Ctotal, // NOLINT(readability-identifier-naming)
const std::array<double, 3>& gravity_earth = {{0., 0., -9.81}}) const noexcept;
/**
* Calculates the gravity vector. Unit: \f$[Nm]\f$.
*
* @param[in] robot_state State from which the gravity vector should be calculated.
* @param[in] gravity_earth Earth's gravity vector. Unit: \f$\frac{m}{s^2}\f$.
* Default to {0.0, 0.0, -9.81}.
*
* @return Gravity vector.
*/
std::array<double, 7> gravity(const franka::RobotState& robot_state,
const std::array<double, 3>& gravity_earth = {
{0., 0., -9.81}}) const noexcept;
/// @cond DO_NOT_DOCUMENT
Model(const Model&) = delete;
Model& operator=(const Model&) = delete;
/// @endcond
private:
std::unique_ptr<ModelLibrary> library_;
};
} // namespace franka