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,
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 
55  std::array<double, 16> F_T_EE{}; // NOLINT(readability-identifier-naming)
56 
64  std::array<double, 16> EE_T_K{}; // NOLINT(readability-identifier-naming)
65 
70  double m_ee{};
71 
76  std::array<double, 9> I_ee{}; // NOLINT(readability-identifier-naming)
77 
82  std::array<double, 3> F_x_Cee{}; // NOLINT(readability-identifier-naming)
83 
88  double m_load{};
89 
94  std::array<double, 9> I_load{}; // NOLINT(readability-identifier-naming)
95 
100  std::array<double, 3> F_x_Cload{}; // NOLINT(readability-identifier-naming)
101 
106  double m_total{};
107 
113  std::array<double, 9> I_total{}; // NOLINT(readability-identifier-naming)
114 
120  std::array<double, 3> F_x_Ctotal{}; // NOLINT(readability-identifier-naming)
121 
129  std::array<double, 2> elbow{};
130 
138  std::array<double, 2> elbow_d{};
139 
147  std::array<double, 2> elbow_c{};
148 
156  std::array<double, 2> delbow_c{};
157 
165  std::array<double, 2> ddelbow_c{};
166 
171  std::array<double, 7> tau_J{}; // NOLINT(readability-identifier-naming)
172 
177  std::array<double, 7> tau_J_d{}; // NOLINT(readability-identifier-naming)
178 
183  std::array<double, 7> dtau_J{}; // NOLINT(readability-identifier-naming)
184 
189  std::array<double, 7> q{};
190 
195  std::array<double, 7> q_d{};
196 
201  std::array<double, 7> dq{};
202 
207  std::array<double, 7> dq_d{};
208 
213  std::array<double, 7> ddq_d{};
214 
221  std::array<double, 7> joint_contact{};
222 
229  std::array<double, 6> cartesian_contact{};
230 
238  std::array<double, 7> joint_collision{};
239 
247  std::array<double, 6> cartesian_collision{};
248 
253  std::array<double, 7> tau_ext_hat_filtered{};
254 
261  std::array<double, 6> O_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
262 
269  std::array<double, 6> K_F_ext_hat_K{}; // NOLINT(readability-identifier-naming)
270 
276  std::array<double, 6> O_dP_EE_d{}; // NOLINT(readability-identifier-naming)
277 
283  std::array<double, 16> O_T_EE_c{}; // NOLINT(readability-identifier-naming)
284 
290  std::array<double, 6> O_dP_EE_c{}; // NOLINT(readability-identifier-naming)
291 
298  std::array<double, 6> O_ddP_EE_c{}; // NOLINT(readability-identifier-naming)
299 
304  std::array<double, 7> theta{};
305 
310  std::array<double, 7> dtheta{};
311 
315  Errors current_errors{};
316 
320  Errors last_motion_errors{};
321 
329  double control_command_success_rate{};
330 
335 
342  Duration time{};
343 };
344 
354 std::ostream& operator<<(std::ostream& ostream, const franka::RobotState& robot_state);
355 
356 } // namespace franka
Contains the franka::Errors type.
RobotMode
Describes the robot&#39;s current mode.
Definition: robot_state.h:22
Enumerates errors that can occur while controlling a franka::Robot.
Definition: errors.h:18
Represents a duration with millisecond resolution.
Definition: duration.h:19
Contains the franka::Duration type.
Describes the robot state.
Definition: robot_state.h:35
std::ostream & operator<<(std::ostream &ostream, const Errors &errors)
Streams the errors as JSON array.


libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01