Flexiv RDK APIs  1.7.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 
137  std::array<double, kCartDoF> K_x_nom = {};
138 
143  std::vector<double> K_q_nom = {};
144 
149  std::vector<double> q_min = {};
150 
155  std::vector<double> q_max = {};
156 
161  std::vector<double> dq_max = {};
162 
167  std::vector<double> tau_max = {};
168 };
169 
176 {
183  std::vector<double> q = {};
184 
193  std::vector<double> theta = {};
194 
202  std::vector<double> dq = {};
203 
211  std::vector<double> dtheta = {};
212 
219  std::vector<double> tau = {};
220 
228  std::vector<double> tau_des = {};
229 
236  std::vector<double> tau_dot = {};
237 
245  std::vector<double> tau_ext = {};
246 
252  std::array<double, kPoseSize> tcp_pose = {};
253 
260  std::array<double, kCartDoF> tcp_vel = {};
261 
267  std::array<double, kPoseSize> flange_pose = {};
268 
275  std::array<double, kCartDoF> ft_sensor_raw = {};
276 
283  std::array<double, kCartDoF> ext_wrench_in_tcp = {};
284 
291  std::array<double, kCartDoF> ext_wrench_in_world = {};
292 
296  std::array<double, kCartDoF> ext_wrench_in_tcp_raw = {};
297 
301  std::array<double, kCartDoF> ext_wrench_in_world_raw = {};
302 };
303 
309 struct PlanInfo
310 {
312  std::string pt_name = {};
313 
315  std::string node_name = {};
316 
318  std::string node_path = {};
319 
321  std::string node_path_time_period = {};
322 
324  std::string node_path_number = {};
325 
327  std::string assigned_plan_name = {};
328 
330  double velocity_scale = {};
331 
333  bool waiting_for_step = {};
334 };
335 
343 struct JPos
344 {
350  JPos(const std::array<double, kSerialJointDoF>& _q_m,
351  const std::array<double, kMaxExtAxes>& _q_e = {})
352  : q_m(_q_m)
353  , q_e(_q_e)
354  {
355  }
356  JPos() = default;
357 
359  std::array<double, kSerialJointDoF> q_m = {};
360 
364  std::array<double, kMaxExtAxes> q_e = {};
365 
367  std::string str() const;
368 };
369 
377 struct Coord
378 {
387  Coord(const std::array<double, kCartDoF / 2>& _position,
388  const std::array<double, kCartDoF / 2>& _orientation,
389  const std::array<std::string, 2>& _ref_frame,
390  const std::array<double, kSerialJointDoF>& _ref_q_m = {},
391  const std::array<double, kMaxExtAxes>& _ref_q_e = {})
392  : position(_position)
393  , orientation(_orientation)
394  , ref_frame(_ref_frame)
395  , ref_q_m(_ref_q_m)
396  , ref_q_e(_ref_q_e)
397  {
398  }
399  Coord() = default;
400 
402  std::array<double, kCartDoF / 2> position = {};
403 
405  std::array<double, kCartDoF / 2> orientation = {};
406 
414  std::array<std::string, 2> ref_frame = {};
415 
420  std::array<double, kSerialJointDoF> ref_q_m = {};
421 
426  std::array<double, kMaxExtAxes> ref_q_e = {};
427 
429  std::string str() const;
430 };
431 
433 using FlexivDataTypes = std::variant<int, double, std::string, rdk::JPos, rdk::Coord,
434  std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
435  std::vector<rdk::Coord>>;
436 
444 std::ostream& operator<<(std::ostream& ostream, const RobotEvent& robot_event);
445 
452 std::ostream& operator<<(std::ostream& ostream, const RobotInfo& robot_info);
453 
460 std::ostream& operator<<(std::ostream& ostream, const RobotStates& robot_states);
461 
468 std::ostream& operator<<(std::ostream& ostream, const PlanInfo& plan_info);
469 
470 } /* namespace rdk */
471 } /* namespace flexiv */
472 
473 #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:435
Data structure representing the customized data type "COORD" in Flexiv Elements.
Definition: data.hpp:378
std::array< double, kCartDoF/2 > orientation
Definition: data.hpp:405
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:387
std::array< std::string, 2 > ref_frame
Definition: data.hpp:414
std::array< double, kCartDoF/2 > position
Definition: data.hpp:402
std::array< double, kSerialJointDoF > ref_q_m
Definition: data.hpp:420
std::array< double, kMaxExtAxes > ref_q_e
Definition: data.hpp:426
std::string str() const
Data structure representing the customized data type "JPOS" in Flexiv Elements.
Definition: data.hpp:344
JPos(const std::array< double, kSerialJointDoF > &_q_m, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
Definition: data.hpp:350
std::string str() const
std::array< double, kMaxExtAxes > q_e
Definition: data.hpp:364
std::array< double, kSerialJointDoF > q_m
Definition: data.hpp:359
Information of the on-going primitive/plan.
Definition: data.hpp:310
std::string node_name
Definition: data.hpp:315
std::string node_path_time_period
Definition: data.hpp:321
std::string node_path
Definition: data.hpp:318
std::string pt_name
Definition: data.hpp:312
double velocity_scale
Definition: data.hpp:330
std::string assigned_plan_name
Definition: data.hpp:327
std::string node_path_number
Definition: data.hpp:324
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:167
std::vector< double > q_max
Definition: data.hpp:155
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:161
std::array< double, kCartDoF > K_x_nom
Definition: data.hpp:137
std::string model_name
Definition: data.hpp:116
std::vector< double > K_q_nom
Definition: data.hpp:143
std::vector< double > q_min
Definition: data.hpp:149
Robot states data in joint- and Cartesian-space.
Definition: data.hpp:176
std::array< double, kCartDoF > ft_sensor_raw
Definition: data.hpp:275
std::array< double, kCartDoF > ext_wrench_in_world
Definition: data.hpp:291
std::vector< double > dtheta
Definition: data.hpp:211
std::vector< double > q
Definition: data.hpp:183
std::array< double, kCartDoF > ext_wrench_in_tcp
Definition: data.hpp:283
std::vector< double > tau_dot
Definition: data.hpp:236
std::array< double, kCartDoF > ext_wrench_in_tcp_raw
Definition: data.hpp:296
std::vector< double > tau_ext
Definition: data.hpp:245
std::array< double, kPoseSize > tcp_pose
Definition: data.hpp:252
std::vector< double > theta
Definition: data.hpp:193
std::vector< double > dq
Definition: data.hpp:202
std::array< double, kCartDoF > tcp_vel
Definition: data.hpp:260
std::vector< double > tau_des
Definition: data.hpp:228
std::array< double, kCartDoF > ext_wrench_in_world_raw
Definition: data.hpp:301
std::vector< double > tau
Definition: data.hpp:219
std::array< double, kPoseSize > flange_pose
Definition: data.hpp:267