Flexiv RDK APIs  1.9.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 
56 static const std::array<std::string, static_cast<size_t>(OperationalStatus::IN_AUTO_MODE) + 1>
57  kOpStatusNames = {"Unknown status", "Ready", "System booting", "E-Stop not released",
58  "Not enabled", "Releasing brakes", "Minor fault occurred", "Critical fault occurred",
59  "In reduced state", "In recovery state", "In Manual mode", "In regular Auto mode"};
60 
64 enum class CoordType
65 {
66  WORLD,
67  TCP,
68 };
69 
75 struct RobotEvent
76 {
77  enum Level
78  {
79  UNKNOWN = 0,
80  INFO,
81  WARNING,
82  ERROR,
83  CRITICAL,
84  };
85 
87  Level level = UNKNOWN;
88 
90  int id = 0;
91 
93  std::string description = "";
94 
96  std::string consequences = "";
97 
99  std::string probable_causes = "";
100 
102  std::string recommended_actions = "";
103 
105  std::chrono::time_point<std::chrono::system_clock> timestamp;
106 };
107 
113 struct RobotInfo
114 {
116  std::string serial_num = {};
117 
119  std::string software_ver = {};
120 
122  std::string model_name = {};
123 
125  std::string license_type = {};
126 
128  size_t DoF_e = {};
129 
131  size_t DoF_m = {};
132 
135  size_t DoF = {};
136 
141  std::array<double, kCartDoF> K_x_nom = {};
142 
145  std::vector<double> K_q_nom = {};
146 
149  std::vector<double> q_min = {};
150 
153  std::vector<double> q_max = {};
154 
157  std::vector<double> dq_max = {};
158 
161  std::vector<double> tau_max = {};
162 
164  bool has_FT_sensor = false;
165 };
166 
174 {
177  std::pair<int, int> timestamp = {};
178 
184  std::vector<double> q = {};
185 
193  std::vector<double> theta = {};
194 
201  std::vector<double> dq = {};
202 
209  std::vector<double> dtheta = {};
210 
216  std::vector<double> tau = {};
217 
224  std::vector<double> tau_des = {};
225 
231  std::vector<double> tau_dot = {};
232 
239  std::vector<double> tau_ext = {};
240 
246  std::vector<double> tau_interact = {};
247 
253  std::vector<double> temperature = {};
254 
260  std::array<double, kPoseSize> tcp_pose = {};
261 
268  std::array<double, kCartDoF> tcp_vel = {};
269 
275  std::array<double, kPoseSize> flange_pose = {};
276 
283  std::array<double, kCartDoF> ft_sensor_raw = {};
284 
291  std::array<double, kCartDoF> ext_wrench_in_tcp = {};
292 
299  std::array<double, kCartDoF> ext_wrench_in_world = {};
300 
304  std::array<double, kCartDoF> ext_wrench_in_tcp_raw = {};
305 
309  std::array<double, kCartDoF> ext_wrench_in_world_raw = {};
310 };
311 
317 struct PlanInfo
318 {
320  std::string pt_name = {};
321 
323  std::string node_name = {};
324 
326  std::string node_path = {};
327 
329  std::string node_path_time_period = {};
330 
332  std::string node_path_number = {};
333 
335  std::string assigned_plan_name = {};
336 
338  double velocity_scale = {};
339 
341  bool waiting_for_step = {};
342 };
343 
351 struct JPos
352 {
358  JPos(const std::array<double, kSerialJointDoF>& _q_m,
359  const std::array<double, kMaxExtAxes>& _q_e = {})
360  : q_m(_q_m)
361  , q_e(_q_e)
362  {
363  }
364  JPos() = default;
365 
367  std::array<double, kSerialJointDoF> q_m = {};
368 
372  std::array<double, kMaxExtAxes> q_e = {};
373 
375  std::string str() const;
376 };
377 
385 struct Coord
386 {
395  Coord(const std::array<double, kCartDoF / 2>& _position,
396  const std::array<double, kCartDoF / 2>& _orientation,
397  const std::array<std::string, 2>& _ref_frame,
398  const std::array<double, kSerialJointDoF>& _ref_q_m = {},
399  const std::array<double, kMaxExtAxes>& _ref_q_e = {})
400  : position(_position)
401  , orientation(_orientation)
402  , ref_frame(_ref_frame)
403  , ref_q_m(_ref_q_m)
404  , ref_q_e(_ref_q_e)
405  {
406  }
407  Coord() = default;
408 
410  std::array<double, kCartDoF / 2> position = {};
411 
413  std::array<double, kCartDoF / 2> orientation = {};
414 
422  std::array<std::string, 2> ref_frame = {};
423 
428  std::array<double, kSerialJointDoF> ref_q_m = {};
429 
434  std::array<double, kMaxExtAxes> ref_q_e = {};
435 
437  std::string str() const;
438 };
439 
441 using FlexivDataTypes = std::variant<int, double, std::string, rdk::JPos, rdk::Coord,
442  std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
443  std::vector<rdk::Coord>>;
444 
452 std::ostream& operator<<(std::ostream& ostream, const RobotEvent& robot_event);
453 
460 std::ostream& operator<<(std::ostream& ostream, const RobotInfo& robot_info);
461 
468 std::ostream& operator<<(std::ostream& ostream, const RobotStates& robot_states);
469 
476 std::ostream& operator<<(std::ostream& ostream, const PlanInfo& plan_info);
477 
478 } /* namespace rdk */
479 } /* namespace flexiv */
480 
481 #endif /* FLEXIV_RDK_DATA_HPP_ */
CoordType
Type of commonly-used reference coordinates.
Definition: data.hpp:65
@ 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:443
Data structure representing the customized data type "COORD" in Flexiv Elements.
Definition: data.hpp:386
std::array< double, kCartDoF/2 > orientation
Definition: data.hpp:413
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:395
std::array< std::string, 2 > ref_frame
Definition: data.hpp:422
std::array< double, kCartDoF/2 > position
Definition: data.hpp:410
std::array< double, kSerialJointDoF > ref_q_m
Definition: data.hpp:428
std::array< double, kMaxExtAxes > ref_q_e
Definition: data.hpp:434
std::string str() const
Data structure representing the customized data type "JPOS" in Flexiv Elements.
Definition: data.hpp:352
JPos(const std::array< double, kSerialJointDoF > &_q_m, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
Definition: data.hpp:358
std::string str() const
std::array< double, kMaxExtAxes > q_e
Definition: data.hpp:372
std::array< double, kSerialJointDoF > q_m
Definition: data.hpp:367
Information of the on-going primitive/plan.
Definition: data.hpp:318
std::string node_name
Definition: data.hpp:323
std::string node_path_time_period
Definition: data.hpp:329
std::string node_path
Definition: data.hpp:326
std::string pt_name
Definition: data.hpp:320
double velocity_scale
Definition: data.hpp:338
std::string assigned_plan_name
Definition: data.hpp:335
std::string node_path_number
Definition: data.hpp:332
Information about a robot event.
Definition: data.hpp:76
std::string probable_causes
Definition: data.hpp:99
std::string consequences
Definition: data.hpp:96
std::chrono::time_point< std::chrono::system_clock > timestamp
Definition: data.hpp:105
std::string description
Definition: data.hpp:93
std::string recommended_actions
Definition: data.hpp:102
General information about the connected robot.
Definition: data.hpp:114
std::vector< double > tau_max
Definition: data.hpp:161
std::vector< double > q_max
Definition: data.hpp:153
std::string license_type
Definition: data.hpp:125
std::string serial_num
Definition: data.hpp:116
std::string software_ver
Definition: data.hpp:119
std::vector< double > dq_max
Definition: data.hpp:157
std::array< double, kCartDoF > K_x_nom
Definition: data.hpp:141
std::string model_name
Definition: data.hpp:122
std::vector< double > K_q_nom
Definition: data.hpp:145
std::vector< double > q_min
Definition: data.hpp:149
Robot states data in joint and Cartesian space.
Definition: data.hpp:174
std::array< double, kCartDoF > ft_sensor_raw
Definition: data.hpp:283
std::array< double, kCartDoF > ext_wrench_in_world
Definition: data.hpp:299
std::vector< double > dtheta
Definition: data.hpp:209
std::vector< double > q
Definition: data.hpp:184
std::pair< int, int > timestamp
Definition: data.hpp:177
std::vector< double > temperature
Definition: data.hpp:253
std::array< double, kCartDoF > ext_wrench_in_tcp
Definition: data.hpp:291
std::vector< double > tau_dot
Definition: data.hpp:231
std::array< double, kCartDoF > ext_wrench_in_tcp_raw
Definition: data.hpp:304
std::vector< double > tau_ext
Definition: data.hpp:239
std::array< double, kPoseSize > tcp_pose
Definition: data.hpp:260
std::vector< double > theta
Definition: data.hpp:193
std::vector< double > dq
Definition: data.hpp:201
std::array< double, kCartDoF > tcp_vel
Definition: data.hpp:268
std::vector< double > tau_des
Definition: data.hpp:224
std::array< double, kCartDoF > ext_wrench_in_world_raw
Definition: data.hpp:309
std::vector< double > tau
Definition: data.hpp:216
std::vector< double > tau_interact
Definition: data.hpp:246
std::array< double, kPoseSize > flange_pose
Definition: data.hpp:275