Flexiv RDK APIs  1.8.0
data.hpp
Go to the documentation of this file.
1 
7 #ifndef FLEXIV_RDK_DATA_HPP_
8 #define FLEXIV_RDK_DATA_HPP_
9 
10 #include <array>
11 #include <vector>
12 #include <string>
13 #include <ostream>
14 #include <variant>
15 #include <chrono>
16 
17 namespace flexiv {
18 namespace rdk {
20 constexpr size_t kCartDoF = 6;
21 
23 constexpr size_t kSerialJointDoF = 7;
24 
26 constexpr size_t kPoseSize = 7;
27 
29 constexpr size_t kIOPorts = 18;
30 
32 constexpr size_t kMaxExtAxes = 6;
33 
40 {
41  UNKNOWN = 0,
42  READY,
43  BOOTING,
45  NOT_ENABLED,
47  MINOR_FAULT,
52  IN_AUTO_MODE,
53 };
54 
58 enum class CoordType
59 {
60  WORLD,
61  TCP,
62 };
63 
69 struct RobotEvent
70 {
71  enum Level
72  {
73  UNKNOWN = 0,
74  INFO,
75  WARNING,
76  ERROR,
77  CRITICAL,
78  };
79 
81  Level level = UNKNOWN;
82 
84  int id = 0;
85 
87  std::string description = "";
88 
90  std::string consequences = "";
91 
93  std::string probable_causes = "";
94 
96  std::string recommended_actions = "";
97 
99  std::chrono::time_point<std::chrono::system_clock> timestamp;
100 };
101 
107 struct RobotInfo
108 {
110  std::string serial_num = {};
111 
113  std::string software_ver = {};
114 
116  std::string model_name = {};
117 
119  std::string license_type = {};
120 
122  size_t DoF_e = {};
123 
125  size_t DoF_m = {};
126 
129  size_t DoF = {};
130 
135  std::array<double, kCartDoF> K_x_nom = {};
136 
139  std::vector<double> K_q_nom = {};
140 
143  std::vector<double> q_min = {};
144 
147  std::vector<double> q_max = {};
148 
151  std::vector<double> dq_max = {};
152 
155  std::vector<double> tau_max = {};
156 
158  bool has_FT_sensor = false;
159 };
160 
168 {
171  std::pair<int, int> timestamp = {};
172 
178  std::vector<double> q = {};
179 
187  std::vector<double> theta = {};
188 
195  std::vector<double> dq = {};
196 
203  std::vector<double> dtheta = {};
204 
210  std::vector<double> tau = {};
211 
218  std::vector<double> tau_des = {};
219 
225  std::vector<double> tau_dot = {};
226 
233  std::vector<double> tau_ext = {};
234 
240  std::vector<double> tau_interact = {};
241 
247  std::vector<double> temperature = {};
248 
254  std::array<double, kPoseSize> tcp_pose = {};
255 
262  std::array<double, kCartDoF> tcp_vel = {};
263 
269  std::array<double, kPoseSize> flange_pose = {};
270 
277  std::array<double, kCartDoF> ft_sensor_raw = {};
278 
285  std::array<double, kCartDoF> ext_wrench_in_tcp = {};
286 
293  std::array<double, kCartDoF> ext_wrench_in_world = {};
294 
298  std::array<double, kCartDoF> ext_wrench_in_tcp_raw = {};
299 
303  std::array<double, kCartDoF> ext_wrench_in_world_raw = {};
304 };
305 
311 struct PlanInfo
312 {
314  std::string pt_name = {};
315 
317  std::string node_name = {};
318 
320  std::string node_path = {};
321 
323  std::string node_path_time_period = {};
324 
326  std::string node_path_number = {};
327 
329  std::string assigned_plan_name = {};
330 
332  double velocity_scale = {};
333 
335  bool waiting_for_step = {};
336 };
337 
345 struct JPos
346 {
352  JPos(const std::array<double, kSerialJointDoF>& _q_m,
353  const std::array<double, kMaxExtAxes>& _q_e = {})
354  : q_m(_q_m)
355  , q_e(_q_e)
356  {
357  }
358  JPos() = default;
359 
361  std::array<double, kSerialJointDoF> q_m = {};
362 
366  std::array<double, kMaxExtAxes> q_e = {};
367 
369  std::string str() const;
370 };
371 
379 struct Coord
380 {
389  Coord(const std::array<double, kCartDoF / 2>& _position,
390  const std::array<double, kCartDoF / 2>& _orientation,
391  const std::array<std::string, 2>& _ref_frame,
392  const std::array<double, kSerialJointDoF>& _ref_q_m = {},
393  const std::array<double, kMaxExtAxes>& _ref_q_e = {})
394  : position(_position)
395  , orientation(_orientation)
396  , ref_frame(_ref_frame)
397  , ref_q_m(_ref_q_m)
398  , ref_q_e(_ref_q_e)
399  {
400  }
401  Coord() = default;
402 
404  std::array<double, kCartDoF / 2> position = {};
405 
407  std::array<double, kCartDoF / 2> orientation = {};
408 
416  std::array<std::string, 2> ref_frame = {};
417 
422  std::array<double, kSerialJointDoF> ref_q_m = {};
423 
428  std::array<double, kMaxExtAxes> ref_q_e = {};
429 
431  std::string str() const;
432 };
433 
435 using FlexivDataTypes = std::variant<int, double, std::string, rdk::JPos, rdk::Coord,
436  std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
437  std::vector<rdk::Coord>>;
438 
446 std::ostream& operator<<(std::ostream& ostream, const RobotEvent& robot_event);
447 
454 std::ostream& operator<<(std::ostream& ostream, const RobotInfo& robot_info);
455 
462 std::ostream& operator<<(std::ostream& ostream, const RobotStates& robot_states);
463 
470 std::ostream& operator<<(std::ostream& ostream, const PlanInfo& plan_info);
471 
472 } /* namespace rdk */
473 } /* namespace flexiv */
474 
475 #endif /* FLEXIV_RDK_DATA_HPP_ */
CoordType
Type of commonly-used reference coordinates.
Definition: data.hpp:59
@ WORLD
World frame (fixed).
@ TCP
TCP frame (move with the robot's end effector).
std::ostream & operator<<(std::ostream &ostream, const RobotEvent &robot_event)
Operator overloading to out stream all members of RobotEvent in JSON format.
constexpr size_t kMaxExtAxes
Definition: data.hpp:32
constexpr size_t kPoseSize
Definition: data.hpp:26
constexpr size_t kSerialJointDoF
Definition: data.hpp:23
constexpr size_t kCartDoF
Definition: data.hpp:20
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
Definition: data.hpp:40
@ IN_RECOVERY_STATE
In recovery state, see recovery().
@ ESTOP_NOT_RELEASED
E-Stop is not released.
@ READY
Ready to be operated.
@ IN_MANUAL_MODE
In Manual mode, need to switch to Auto (Remote) mode.
@ IN_AUTO_MODE
In regular Auto mode, need to switch to Auto (Remote) mode.
@ CRITICAL_FAULT
Critical fault occurred, call ClearFault() to try clearing it.
@ RELEASING_BRAKE
Brake release in progress, please wait.
@ IN_REDUCED_STATE
In reduced state, see reduced().
@ NOT_ENABLED
Not enabled, call Enable() to send the signal.
@ MINOR_FAULT
Minor fault occurred, call ClearFault() to try clearing it.
@ BOOTING
System still booting, please wait.
constexpr size_t kIOPorts
Definition: data.hpp:29
std::variant< int, double, std::string, rdk::JPos, rdk::Coord, std::vector< int >, std::vector< double >, std::vector< std::string >, std::vector< rdk::JPos >, std::vector< rdk::Coord > > FlexivDataTypes
Definition: data.hpp:437
Data structure representing the customized data type "COORD" in Flexiv Elements.
Definition: data.hpp:380
std::array< double, kCartDoF/2 > orientation
Definition: data.hpp:407
Coord(const std::array< double, kCartDoF/2 > &_position, const std::array< double, kCartDoF/2 > &_orientation, const std::array< std::string, 2 > &_ref_frame, const std::array< double, kSerialJointDoF > &_ref_q_m={}, const std::array< double, kMaxExtAxes > &_ref_q_e={})
Construct an instance of Coord.
Definition: data.hpp:389
std::array< std::string, 2 > ref_frame
Definition: data.hpp:416
std::array< double, kCartDoF/2 > position
Definition: data.hpp:404
std::array< double, kSerialJointDoF > ref_q_m
Definition: data.hpp:422
std::array< double, kMaxExtAxes > ref_q_e
Definition: data.hpp:428
std::string str() const
Data structure representing the customized data type "JPOS" in Flexiv Elements.
Definition: data.hpp:346
JPos(const std::array< double, kSerialJointDoF > &_q_m, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
Definition: data.hpp:352
std::string str() const
std::array< double, kMaxExtAxes > q_e
Definition: data.hpp:366
std::array< double, kSerialJointDoF > q_m
Definition: data.hpp:361
Information of the on-going primitive/plan.
Definition: data.hpp:312
std::string node_name
Definition: data.hpp:317
std::string node_path_time_period
Definition: data.hpp:323
std::string node_path
Definition: data.hpp:320
std::string pt_name
Definition: data.hpp:314
double velocity_scale
Definition: data.hpp:332
std::string assigned_plan_name
Definition: data.hpp:329
std::string node_path_number
Definition: data.hpp:326
Information about a robot event.
Definition: data.hpp:70
std::string probable_causes
Definition: data.hpp:93
std::string consequences
Definition: data.hpp:90
std::chrono::time_point< std::chrono::system_clock > timestamp
Definition: data.hpp:99
std::string description
Definition: data.hpp:87
std::string recommended_actions
Definition: data.hpp:96
General information about the connected robot.
Definition: data.hpp:108
std::vector< double > tau_max
Definition: data.hpp:155
std::vector< double > q_max
Definition: data.hpp:147
std::string license_type
Definition: data.hpp:119
std::string serial_num
Definition: data.hpp:110
std::string software_ver
Definition: data.hpp:113
std::vector< double > dq_max
Definition: data.hpp:151
std::array< double, kCartDoF > K_x_nom
Definition: data.hpp:135
std::string model_name
Definition: data.hpp:116
std::vector< double > K_q_nom
Definition: data.hpp:139
std::vector< double > q_min
Definition: data.hpp:143
Robot states data in joint and Cartesian space.
Definition: data.hpp:168
std::array< double, kCartDoF > ft_sensor_raw
Definition: data.hpp:277
std::array< double, kCartDoF > ext_wrench_in_world
Definition: data.hpp:293
std::vector< double > dtheta
Definition: data.hpp:203
std::vector< double > q
Definition: data.hpp:178
std::pair< int, int > timestamp
Definition: data.hpp:171
std::vector< double > temperature
Definition: data.hpp:247
std::array< double, kCartDoF > ext_wrench_in_tcp
Definition: data.hpp:285
std::vector< double > tau_dot
Definition: data.hpp:225
std::array< double, kCartDoF > ext_wrench_in_tcp_raw
Definition: data.hpp:298
std::vector< double > tau_ext
Definition: data.hpp:233
std::array< double, kPoseSize > tcp_pose
Definition: data.hpp:254
std::vector< double > theta
Definition: data.hpp:187
std::vector< double > dq
Definition: data.hpp:195
std::array< double, kCartDoF > tcp_vel
Definition: data.hpp:262
std::vector< double > tau_des
Definition: data.hpp:218
std::array< double, kCartDoF > ext_wrench_in_world_raw
Definition: data.hpp:303
std::vector< double > tau
Definition: data.hpp:210
std::vector< double > tau_interact
Definition: data.hpp:240
std::array< double, kPoseSize > flange_pose
Definition: data.hpp:269