franka/robot/robot_state.rs
1// Copyright (c) 2021 Marco Boneberger
2// Licensed under the EUPL-1.2-or-later
3
4//! Contains the franka::RobotState types.
5use std::time::Duration;
6
7use crate::robot::errors::{FrankaErrorKind, FrankaErrors};
8use crate::robot::types::{RobotMode, RobotStateIntern};
9use nalgebra::{Matrix3, Vector3};
10
11/// Describes the robot state.
12#[derive(Debug, Clone, Default)]
13#[allow(non_snake_case)]
14pub struct RobotState {
15 /// 
16 ///
17 /// Measured end effector pose in base frame.
18 /// Pose is represented as a 4x4 matrix in column-major format.
19 pub O_T_EE: [f64; 16],
20 /// 
21 ///
22 /// Last desired end effector pose of motion generation in base frame.
23 /// Pose is represented as a 4x4 matrix in column-major format.
24 pub O_T_EE_d: [f64; 16],
25 /// 
26 ///
27 /// End effector frame pose in flange frame.
28 /// Pose is represented as a 4x4 matrix in column-major format.
29 /// # See
30 /// * [`F_T_NE`](`Self::F_T_NE`)
31 /// * [`NE_T_EE`](`Self::NE_T_EE`)
32 /// * [`Robot`](`crate::Robot`) for an explanation of the NE and EE frames.
33 pub F_T_EE: [f64; 16],
34 /// 
35 ///
36 /// Nominal end effector frame pose in flange frame.
37 /// Pose is represented as a 4x4 matrix in column-major format.
38 /// # See
39 /// * [`F_T_NE`](`Self::F_T_NE`)
40 /// * [`NE_T_EE`](`Self::NE_T_EE`)
41 /// * [`Robot`](`crate::Robot`) for an explanation of the NE and EE frames.
42 pub F_T_NE: [f64; 16],
43 /// 
44 ///
45 /// End effector frame pose in nominal end effector frame.
46 /// Pose is represented as a 4x4 matrix in column-major format.
47 /// # See
48 /// * [`F_T_NE`](`Self::F_T_NE`)
49 /// * [`NE_T_EE`](`Self::NE_T_EE`)
50 /// * [`Robot`](`crate::Robot`) for an explanation of the NE and EE frames.
51 pub NE_T_EE: [f64; 16],
52 /// 
53 ///
54 /// Stiffness frame pose in end effector frame.
55 /// Pose is represented as a 4x4 matrix in column-major format.
56 ///
57 /// See also [K-Frame](`crate::Robot#stiffness-frame-k`)
58 pub EE_T_K: [f64; 16],
59 /// 
60 ///
61 /// Configured mass of the end effector.
62 pub m_ee: f64,
63 /// 
64 ///
65 /// Configured rotational inertia matrix of the end effector load with respect to center of mass.
66 pub I_ee: [f64; 9],
67 /// 
68 ///
69 /// Configured center of mass of the end effector load with respect to flange frame.
70 pub F_x_Cee: [f64; 3],
71 /// 
72 ///
73 /// Configured mass of the external load.
74 pub m_load: f64,
75 /// 
76 ///
77 /// Configured rotational inertia matrix of the external load with respect to center of mass.
78 pub I_load: [f64; 9],
79 /// 
80 ///
81 /// Configured center of mass of the external load with respect to flange frame.
82 pub F_x_Cload: [f64; 3],
83 /// 
84 ///
85 /// Sum of the mass of the end effector and the external load.
86 pub m_total: f64,
87 /// 
88 ///
89 /// Combined rotational inertia matrix of the end effector load and the external load with respect
90 /// to the center of mass.
91 pub I_total: [f64; 9],
92 /// 
93 ///
94 /// Combined center of mass of the end effector load and the external load with respect to flange
95 /// frame.
96 pub F_x_Ctotal: [f64; 3],
97 /// Elbow configuration.
98 ///
99 /// The values of the array are:
100 /// - \[0\] Position of the 3rd joint in \[rad\].
101 /// - \[1\] Sign of the 4th joint. Can be +1 or -1.
102 pub elbow: [f64; 2],
103 /// Desired elbow configuration.
104 ///
105 /// The values of the array are:
106 /// - \[0\] Position of the 3rd joint in \[rad\].
107 /// - \[1\] Sign of the 4th joint. Can be +1 or -1.
108 pub elbow_d: [f64; 2],
109 /// Commanded elbow configuration.
110 ///
111 /// The values of the array are:
112 /// - \[0\] Position of the 3rd joint in \[rad\].
113 /// - \[1\] Sign of the 4th joint. Can be +1 or -1.
114 pub elbow_c: [f64; 2],
115 /// Commanded elbow velocity.
116 ///
117 /// The values of the array are:
118 /// - \[0\] Velocity of the 3rd joint in \[rad/s\].
119 /// - \[1\] Sign of the 4th joint. Can be +1 or -1.
120 pub delbow_c: [f64; 2],
121 /// Commanded elbow acceleration.
122 ///
123 /// The values of the array are:
124 /// - \[0\] Acceleration of the 3rd joint in \[rad/s^2\].
125 /// - \[1\] Sign of the 4th joint. Can be +1 or -1.
126 pub ddelbow_c: [f64; 2],
127 /// 
128 ///
129 /// Measured link-side joint torque sensor signals. Unit: \[Nm\]
130 pub tau_J: [f64; 7],
131 /// 
132 ///
133 /// Desired link-side joint torque sensor signals without gravity. Unit: \[Nm\]
134 pub tau_J_d: [f64; 7],
135 /// 
136 ///
137 /// Derivative of measured link-side joint torque sensor signals. Unit: [Nm/s]
138 pub dtau_J: [f64; 7],
139 /// 
140 ///
141 /// Measured joint position. Unit: \[rad\]
142 pub q: [f64; 7],
143 /// 
144 ///
145 /// Desired joint position. Unit: \[rad\]
146 pub q_d: [f64; 7],
147 /// 
148 ///
149 /// Measured joint velocity. Unit: \[rad/s\]
150 pub dq: [f64; 7],
151 /// 
152 ///
153 /// Desired joint velocity. Unit: \[rad/s\]
154 pub dq_d: [f64; 7],
155 /// 
156 ///
157 /// Desired joint acceleration. Unit: \[rad/s^2\]
158 pub ddq_d: [f64; 7],
159 /// Indicates which contact level is activated in which joint. After contact disappears, value
160 /// turns to zero.
161 ///
162 /// See [`Robot::set_collision_behavior`](`crate::Robot::set_collision_behavior`)
163 /// for setting sensitivity values.
164 pub joint_contact: [f64; 7],
165 /// Indicates which contact level is activated in which Cartesian dimension (x,y,z,R,P,Y).
166 /// After contact disappears, the value turns to zero.
167 ///
168 /// See [`Robot::set_collision_behavior`](`crate::Robot::set_collision_behavior`)
169 /// for setting sensitivity values.
170 pub cartesian_contact: [f64; 6],
171 /// Indicates which contact level is activated in which joint. After contact disappears, the value
172 /// stays the same until a reset command is sent.
173 ///
174 /// See [`Robot::set_collision_behavior`](`crate::Robot::set_collision_behavior`)
175 /// for setting sensitivity values.
176 ///
177 /// See [`Robot::automatic_error_recovery`](`crate::Robot::automatic_error_recovery`)
178 /// for performing a reset after a collision.
179 pub joint_collision: [f64; 7],
180 /// Indicates which contact level is activated in which Cartesian dimension (x,y,z,R,P,Y).
181 /// After contact disappears, the value stays the same until a reset command is sent.
182 ///
183 /// See [`Robot::set_collision_behavior`](`crate::Robot::set_collision_behavior`)
184 /// for setting sensitivity values.
185 ///
186 /// See [`Robot::automatic_error_recovery`](`crate::Robot::automatic_error_recovery`)
187 /// for performing a reset after a collision.
188 pub cartesian_collision: [f64; 6],
189 /// 
190 ///
191 /// External torque, filtered. Unit: \[Nm\]
192 pub tau_ext_hat_filtered: [f64; 7],
193 /// 
194 ///
195 /// Estimated external wrench (force, torque) acting on stiffness frame, expressed
196 /// relative to the base frame. See also @ref k-frame "K frame".
197 /// Unit: \[N,N,N,Nm,Nm,Nm\].
198 pub O_F_ext_hat_K: [f64; 6],
199 /// 
200 ///
201 /// Estimated external wrench (force, torque) acting on stiffness frame,
202 /// expressed relative to the stiffness frame. See also @ref k-frame "K frame".
203 /// Unit: \[N,N,N,Nm,Nm,Nm\].
204 pub K_F_ext_hat_K: [f64; 6],
205 /// 
206 ///
207 /// Desired end effector twist in base frame.
208 /// Unit: [m/s,m/s,m/s,rad/s,rad/s,rad/s]
209 pub O_dP_EE_d: [f64; 6],
210 /// 
211 ///
212 /// Linear component of the acceleration of the robot's base, expressed in frame parallel to the
213 /// base frame, i.e. the base's translational acceleration. If the base is resting
214 /// this shows the direction of the gravity vector. It is hardcoded for now to `{0, 0, -9.81}`.
215 pub O_ddP_O: [f64; 3],
216 /// 
217 ///
218 /// Last commanded end effector pose of motion generation in base frame.
219 /// Pose is represented as a 4x4 matrix in column-major format.
220 pub O_T_EE_c: [f64; 16],
221 /// 
222 ///
223 /// Last commanded end effector twist in base frame.
224 /// Unit: [m/s,m/s,m/s,rad/s,rad/s,rad/s]
225 pub O_dP_EE_c: [f64; 6],
226 ///
227 ///
228 /// Last commanded end effector acceleration in base frame.
229 /// Unit: [m/s^2,m/s^2,m/s^2,rad/s^2,rad/s^2,rad/s^2]
230 pub O_ddP_EE_c: [f64; 6],
231 /// 
232 ///
233 /// Motor position. Unit: \[rad\]
234 pub theta: [f64; 7],
235 /// 
236 ///
237 /// Motor velocity. Unit: \[rad/s\]
238 pub dtheta: [f64; 7],
239 /// Current error state.
240 pub current_errors: FrankaErrors,
241 /// Contains the errors that aborted the previous motion
242 pub last_motion_errors: FrankaErrors,
243 /// Percentage of the last 100 control commands that were successfully received by the robot.
244 ///
245 /// Shows a value of zero if no control or motion generator loop is currently running.
246 ///
247 /// Range \[0,1\]
248 pub control_command_success_rate: f64,
249 /// Current robot mode.
250 pub robot_mode: RobotMode,
251 /// Strictly monotonically increasing timestamp since robot start.
252 ///
253 /// Inside of control loops "time_step" parameter of Robot::control can be used
254 /// instead
255 pub time: Duration,
256}
257impl From<RobotStateIntern> for RobotState {
258 #[allow(non_snake_case)]
259 fn from(robot_state: RobotStateIntern) -> Self {
260 let O_T_EE = robot_state.O_T_EE;
261 let O_T_EE_d = robot_state.O_T_EE_d;
262 let F_T_NE = robot_state.F_T_NE;
263 let NE_T_EE = robot_state.NE_T_EE;
264 let F_T_EE = robot_state.F_T_EE;
265 let EE_T_K = robot_state.EE_T_K;
266 let m_ee = robot_state.m_ee;
267 let F_x_Cee = robot_state.F_x_Cee;
268 let I_ee = robot_state.I_ee;
269 let m_load = robot_state.m_load;
270 let F_x_Cload = robot_state.F_x_Cload;
271 let I_load = robot_state.I_load;
272 let m_total = robot_state.m_ee + robot_state.m_load;
273 let F_x_Ctotal = combine_center_of_mass(
274 robot_state.m_ee,
275 robot_state.F_x_Cee,
276 robot_state.m_load,
277 robot_state.F_x_Cload,
278 );
279 let I_total = combine_inertia_tensor(
280 robot_state.m_ee,
281 robot_state.F_x_Cee,
282 robot_state.I_ee,
283 robot_state.m_load,
284 robot_state.F_x_Cload,
285 robot_state.I_load,
286 m_total,
287 F_x_Ctotal,
288 );
289 let elbow = robot_state.elbow;
290 let elbow_d = robot_state.elbow_d;
291 let elbow_c = robot_state.elbow_c;
292 let delbow_c = robot_state.delbow_c;
293 let ddelbow_c = robot_state.ddelbow_c;
294 let tau_J = robot_state.tau_J;
295 let tau_J_d = robot_state.tau_J_d;
296 let dtau_J = robot_state.dtau_J;
297 let q = robot_state.q;
298 let dq = robot_state.dq;
299 let q_d = robot_state.q_d;
300 let dq_d = robot_state.dq_d;
301 let ddq_d = robot_state.ddq_d;
302 let joint_contact = robot_state.joint_contact;
303 let cartesian_contact = robot_state.cartesian_contact;
304 let joint_collision = robot_state.joint_collision;
305 let cartesian_collision = robot_state.cartesian_collision;
306 let tau_ext_hat_filtered = robot_state.tau_ext_hat_filtered;
307 let O_F_ext_hat_K = robot_state.O_F_ext_hat_K;
308 let K_F_ext_hat_K = robot_state.K_F_ext_hat_K;
309 let O_dP_EE_d = robot_state.O_dP_EE_d;
310 let O_ddP_O = robot_state.O_ddP_O;
311 let O_T_EE_c = robot_state.O_T_EE_c;
312 let O_dP_EE_c = robot_state.O_dP_EE_c;
313 let O_ddP_EE_c = robot_state.O_ddP_EE_c;
314 let theta = robot_state.theta;
315 let dtheta = robot_state.dtheta;
316 let control_command_success_rate = robot_state.control_command_success_rate;
317 let time = Duration::from_millis(robot_state.message_id);
318 let robot_mode = robot_state.robot_mode;
319 let current_errors = FrankaErrors::new(robot_state.errors, FrankaErrorKind::Error);
320 let last_motion_errors =
321 FrankaErrors::new(robot_state.errors, FrankaErrorKind::ReflexReason);
322 RobotState {
323 O_T_EE,
324 O_T_EE_d,
325 F_T_EE,
326 F_T_NE,
327 NE_T_EE,
328 EE_T_K,
329 m_ee,
330 I_ee,
331 F_x_Cee,
332 m_load,
333 I_load,
334 F_x_Cload,
335 m_total,
336 I_total,
337 F_x_Ctotal,
338 elbow,
339 elbow_d,
340 elbow_c,
341 delbow_c,
342 ddelbow_c,
343 tau_J,
344 tau_J_d,
345 dtau_J,
346 q,
347 q_d,
348 dq,
349 dq_d,
350 ddq_d,
351 joint_contact,
352 cartesian_contact,
353 joint_collision,
354 cartesian_collision,
355 tau_ext_hat_filtered,
356 O_F_ext_hat_K,
357 K_F_ext_hat_K,
358 O_dP_EE_d,
359 O_ddP_O,
360 O_T_EE_c,
361 O_dP_EE_c,
362 O_ddP_EE_c,
363 theta,
364 dtheta,
365 current_errors,
366 last_motion_errors,
367 control_command_success_rate,
368 robot_mode,
369 time,
370 }
371 }
372}
373
374#[allow(non_snake_case, clippy::too_many_arguments)]
375fn combine_inertia_tensor(
376 m_ee: f64,
377 F_x_Cee: [f64; 3],
378 I_ee: [f64; 9],
379 m_load: f64,
380 F_x_Cload: [f64; 3],
381 I_load: [f64; 9],
382 m_total: f64,
383 F_x_Ctotal: [f64; 3],
384) -> [f64; 9] {
385 let center_of_mass_ee = Vector3::from_column_slice(&F_x_Cee);
386 let center_of_mass_load = Vector3::from_column_slice(&F_x_Cload);
387 let center_of_mass_total = Vector3::from_column_slice(&F_x_Ctotal);
388
389 let mut inertia_ee = Matrix3::from_column_slice(&I_ee);
390 let mut inertia_load = Matrix3::from_column_slice(&I_load);
391
392 if m_ee == 0. {
393 inertia_ee = Matrix3::zeros();
394 }
395 if m_load == 0. {
396 inertia_load = Matrix3::zeros();
397 }
398 let inertia_ee_flange = inertia_ee
399 - m_ee
400 * (skew_symmetric_matrix_from_vector(¢er_of_mass_ee)
401 * skew_symmetric_matrix_from_vector(¢er_of_mass_ee));
402 let inertia_load_flange = inertia_load
403 - m_load
404 * (skew_symmetric_matrix_from_vector(¢er_of_mass_load)
405 * skew_symmetric_matrix_from_vector(¢er_of_mass_load));
406 let inertia_total_flange = inertia_ee_flange + inertia_load_flange;
407
408 let inertia_total: Matrix3<f64> = inertia_total_flange
409 + m_total
410 * (skew_symmetric_matrix_from_vector(¢er_of_mass_total)
411 * skew_symmetric_matrix_from_vector(¢er_of_mass_total));
412 let mut I_total = [0.; 9];
413 for (i, &x) in inertia_total.as_slice().iter().enumerate() {
414 I_total[i] = x;
415 }
416 I_total
417}
418
419#[allow(non_snake_case)]
420fn combine_center_of_mass(
421 m_ee: f64,
422 F_x_Cee: [f64; 3],
423 m_load: f64,
424 F_x_Cload: [f64; 3],
425) -> [f64; 3] {
426 let mut F_x_Ctotal = [0.; 3];
427 if m_ee + m_load > 0. {
428 for i in 0..F_x_Ctotal.len() {
429 F_x_Ctotal[i] = (m_ee * F_x_Cee[i] + m_load * F_x_Cload[i]) / (m_ee + m_load);
430 }
431 }
432 F_x_Ctotal
433}
434
435fn skew_symmetric_matrix_from_vector(vector: &Vector3<f64>) -> Matrix3<f64> {
436 Matrix3::new(
437 0., -vector.z, vector.y, vector.z, 0., -vector.x, -vector.y, vector.x, 0.,
438 )
439}
440
441#[cfg(test)]
442mod tests {
443 use crate::robot::robot_state::{combine_center_of_mass, combine_inertia_tensor};
444
445 #[test]
446 fn combine_com_test() {
447 let m_ee = 0.;
448 let m_load = 0.;
449 let f_x_ctotal = combine_center_of_mass(m_ee, [0.; 3], m_load, [0.; 3]);
450 f_x_ctotal
451 .iter()
452 .for_each(|&x| assert!(x.abs() < f64::EPSILON));
453
454 let m_ee = 0.73;
455 let m_load = 0.5;
456 let f_x_cee = [-0.01, 0., -0.03];
457 let i_ee = [0.001, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0017];
458 let i_load = [0.001, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.3];
459 let f_x_cload = [0.01, -0.2, 0.03];
460 let m_total = m_ee + m_load;
461 let f_x_ctotal = combine_center_of_mass(m_ee, f_x_cee, m_load, f_x_cload);
462 let i_total = combine_inertia_tensor(
463 m_ee, f_x_cee, i_ee, m_load, f_x_cload, i_load, m_total, f_x_ctotal,
464 );
465 let expected = [
466 1.49382113821138e-02,
467 1.18699186991870e-03,
468 -3.56097560975610e-04,
469 1.18699186991870e-03,
470 2.36869918699187e-02,
471 3.56097560975610e-03,
472 -3.56097560975610e-04,
473 3.56097560975610e-03,
474 3.13688617886179e-01,
475 ];
476 i_total
477 .iter()
478 .zip(expected.iter())
479 .take(3)
480 .for_each(|(&x, &y)| assert!((x - y).abs() < 1e-14));
481 }
482
483 #[test]
484 fn inertia_zero_test() {
485 let m_ee = 0.;
486 let m_load = 0.0;
487 let f_x_cee = [-0.01, 0., -0.03];
488 let i_ee = [0.001, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0017];
489 let i_load = [0.001, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.3];
490 let f_x_cload = [0.01, -0.2, 0.03];
491 let m_total = m_ee + m_load;
492 let f_x_ctotal = combine_center_of_mass(m_ee, f_x_cee, m_load, f_x_cload);
493 let i_total = combine_inertia_tensor(
494 m_ee, f_x_cee, i_ee, m_load, f_x_cload, i_load, m_total, f_x_ctotal,
495 );
496 let expected = [0.; 9];
497 i_total
498 .iter()
499 .zip(expected.iter())
500 .take(3)
501 .for_each(|(&x, &y)| assert!((x - y).abs() < 1e-17));
502
503 let m_ee = 0.;
504 let m_load = 0.5;
505 let f_x_cee = [-0.01, 0., -0.03];
506 let i_ee = [0.001, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0017];
507 let i_load = [0.001, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.3];
508 let f_x_cload = [0.01, -0.2, 0.03];
509 let m_total = m_ee + m_load;
510 let f_x_ctotal = combine_center_of_mass(m_ee, f_x_cee, m_load, f_x_cload);
511 let i_total = combine_inertia_tensor(
512 m_ee, f_x_cee, i_ee, m_load, f_x_cload, i_load, m_total, f_x_ctotal,
513 );
514 let expected = i_load;
515 i_total
516 .iter()
517 .zip(expected.iter())
518 .take(3)
519 .for_each(|(&x, &y)| assert!((x - y).abs() < 1e-17));
520
521 let m_ee = 0.73;
522 let m_load = 0.0;
523 let f_x_cee = [-0.01, 0., -0.03];
524 let i_ee = [0.001, 0.0, 0.0, 0.0, 0.0025, 0.0, 0.0, 0.0, 0.0017];
525 let i_load = [0.001, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.3];
526 let f_x_cload = [0.01, -0.2, 0.03];
527 let m_total = m_ee + m_load;
528 let f_x_ctotal = combine_center_of_mass(m_ee, f_x_cee, m_load, f_x_cload);
529 let i_total = combine_inertia_tensor(
530 m_ee, f_x_cee, i_ee, m_load, f_x_cload, i_load, m_total, f_x_ctotal,
531 );
532 let expected = i_ee;
533 i_total
534 .iter()
535 .zip(expected.iter())
536 .take(3)
537 .for_each(|(&x, &y)| assert!((x - y).abs() < 1e-17));
538 }
539}