libfranka  0.8.0
FCI C++ API
robot_state.h
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika 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 <ostream>
7 
8 #include <franka/duration.h>
9 #include <franka/errors.h>
10 
16 namespace franka {
17 
22 enum class RobotMode {
23  kOther,
24  kIdle,
25  kMove,
26  kGuiding,
27  kReflex,
28  kUserStopped,
29  kAutomaticErrorRecovery
30 };
31 
35 struct RobotState {
41  std::array<double, 16> O_T_EE{}; // NOLINT(readability-identifier-naming)
42 
48  std::array<double, 16> O_T_EE_d{}; // NOLINT(readability-identifier-naming)
49 
59  std::array<double, 16> F_T_EE{}; // NOLINT(readability-identifier-naming)
60 
70  std::array<double, 16> F_T_NE{}; // NOLINT(readability-identifier-naming)
71 
82  std::array<double, 16> NE_T_EE{}; // NOLINT(readability-identifier-naming)
83 
91  std::array<double, 16> EE_T_K{}; // NOLINT(readability-identifier-naming)
92 
97  double m_ee{};
98 
103  std::array<double, 9> I_ee{}; // NOLINT(readability-identifier-naming)
104 
109  std::array<double, 3> F_x_Cee{}; // NOLINT(readability-identifier-naming)
110 
115  double m_load{};
116 
121  std::array<double, 9> I_load{}; // NOLINT(readability-identifier-naming)
122 
127  std::array<double, 3> F_x_Cload{}; // NOLINT(readability-identifier-naming)
128 
133  double m_total{};
134 
140  std::array<double, 9> I_total{}; // NOLINT(readability-identifier-naming)
141 
147  std::array<double, 3> F_x_Ctotal{}; // NOLINT(readability-identifier-naming)
148 
156  std::array<double, 2> elbow{};
157 
165  std::array<double, 2> elbow_d{};
166 
174  std::array<double, 2> elbow_c{};
175 
183  std::array<double, 2> delbow_c{};
184 
192  std::array<double, 2> ddelbow_c{};
193 
198  std::array<double, 7> tau_J{}; // NOLINT(readability-identifier-naming)
199 
204  std::array<double, 7> tau_J_d{}; // NOLINT(readability-identifier-naming)
205 
210  std::array<double, 7> dtau_J{}; // NOLINT(readability-identifier-naming)
211 
216  std::array<double, 7> q{};
217 
222  std::array<double, 7> q_d{};
223 
228  std::array<double, 7> dq{};
229 
234  std::array<double, 7> dq_d{};
235 
240  std::array<double, 7> ddq_d{};
241 
248  std::array<double, 7> joint_contact{};
249 
256  std::array<double, 6> cartesian_contact{};
257 
265  std::array<double, 7> joint_collision{};
266 
274  std::array<double, 6> cartesian_collision{};
275 
280  std::array<double, 7> tau_ext_hat_filtered{};
281 
288  std::array<double, 6> O_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
289 
296  std::array<double, 6> K_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
297 
303  std::array<double, 6> O_dP_EE_d{}; // NOLINT(readability-identifier-naming)
304 
310  std::array<double, 16> O_T_EE_c{}; // NOLINT(readability-identifier-naming)
311 
317  std::array<double, 6> O_dP_EE_c{}; // NOLINT(readability-identifier-naming)
318 
325  std::array<double, 6> O_ddP_EE_c{}; // NOLINT(readability-identifier-naming)
326 
331  std::array<double, 7> theta{};
332 
337  std::array<double, 7> dtheta{};
338 
342  Errors current_errors{};
343 
347  Errors last_motion_errors{};
348 
356  double control_command_success_rate{};
357 
361  RobotMode robot_mode = RobotMode::kUserStopped;
362 
369  Duration time{};
370 };
371 
381 std::ostream& operator<<(std::ostream& ostream, const franka::RobotState& robot_state);
382 
383 } // namespace franka
Contains the franka::Errors type.
std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
Streams the errors as JSON array.
Enumerates errors that can occur while controlling a franka::Robot.
Definition: errors.h:18
Represents a duration with millisecond resolution.
Definition: duration.h:19
Definition: command_types.h:13
Contains the franka::Duration type.
Describes the robot state.
Definition: robot_state.h:35
RobotMode
Describes the robot&#39;s current mode.
Definition: robot_state.h:22