Flexiv RDK APIs  1.5.1
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 
16 namespace flexiv {
17 namespace rdk {
19 constexpr size_t kCartDoF = 6;
20 
22 constexpr size_t kSerialJointDoF = 7;
23 
25 constexpr size_t kPoseSize = 7;
26 
28 constexpr size_t kIOPorts = 18;
29 
31 constexpr size_t kMaxExtAxes = 6;
32 
39 {
40  UNKNOWN = 0,
41  READY,
42  BOOTING,
44  NOT_ENABLED,
46  MINOR_FAULT,
51  IN_AUTO_MODE,
52 };
53 
57 enum class CoordType
58 {
59  WORLD,
60  TCP,
61 };
62 
68 struct RobotInfo
69 {
71  std::string serial_num = {};
72 
74  std::string software_ver = {};
75 
77  std::string model_name = {};
78 
80  std::string license_type = {};
81 
83  size_t DoF = {};
84 
91  std::array<double, kCartDoF> K_x_nom = {};
92 
97  std::vector<double> K_q_nom = {};
98 
103  std::vector<double> q_min = {};
104 
109  std::vector<double> q_max = {};
110 
115  std::vector<double> dq_max = {};
116 
121  std::vector<double> tau_max = {};
122 };
123 
130 {
136  std::vector<double> q = {};
137 
144  std::vector<double> theta = {};
145 
151  std::vector<double> dq = {};
152 
158  std::vector<double> dtheta = {};
159 
164  std::vector<double> tau = {};
165 
170  std::vector<double> tau_des = {};
171 
176  std::vector<double> tau_dot = {};
177 
183  std::vector<double> tau_ext = {};
184 
189  std::vector<double> q_e = {};
190 
195  std::vector<double> dq_e = {};
196 
201  std::vector<double> tau_e = {};
202 
208  std::array<double, kPoseSize> tcp_pose = {};
209 
215  std::array<double, kPoseSize> tcp_pose_des = {};
216 
223  std::array<double, kCartDoF> tcp_vel = {};
224 
230  std::array<double, kPoseSize> flange_pose = {};
231 
238  std::array<double, kCartDoF> ft_sensor_raw = {};
239 
246  std::array<double, kCartDoF> ext_wrench_in_tcp = {};
247 
254  std::array<double, kCartDoF> ext_wrench_in_world = {};
255 
259  std::array<double, kCartDoF> ext_wrench_in_tcp_raw = {};
260 
264  std::array<double, kCartDoF> ext_wrench_in_world_raw = {};
265 };
266 
272 struct PlanInfo
273 {
275  std::string pt_name = {};
276 
278  std::string node_name = {};
279 
281  std::string node_path = {};
282 
284  std::string node_path_time_period = {};
285 
287  std::string node_path_number = {};
288 
290  std::string assigned_plan_name = {};
291 
293  double velocity_scale = {};
294 
296  bool waiting_for_step = {};
297 };
298 
305 {
307  double width = {};
308 
311  double force = {};
312 
314  double max_width = {};
315 };
316 
323 {
325  double mass = 0.0;
326 
328  std::array<double, 3> CoM = {};
329 
331  std::array<double, 6> inertia = {};
332 
336  std::array<double, kPoseSize> tcp_location = {};
337 };
338 
346 struct JPos
347 {
353  JPos(const std::array<double, kSerialJointDoF>& _q,
354  const std::array<double, kMaxExtAxes>& _q_e = {})
355  : q(_q)
356  , q_e(_q_e)
357  {
358  }
359  JPos() = default;
360 
362  std::array<double, kSerialJointDoF> q = {};
363 
367  std::array<double, kMaxExtAxes> q_e = {};
368 
370  std::string str() const;
371 };
372 
380 struct Coord
381 {
390  Coord(const std::array<double, kCartDoF / 2>& _position,
391  const std::array<double, kCartDoF / 2>& _orientation,
392  const std::array<std::string, 2>& _ref_frame,
393  const std::array<double, kSerialJointDoF>& _ref_q = {},
394  const std::array<double, kMaxExtAxes>& _ref_q_e = {})
395  : position(_position)
396  , orientation(_orientation)
397  , ref_frame(_ref_frame)
398  , ref_q(_ref_q)
399  , ref_q_e(_ref_q_e)
400  {
401  }
402  Coord() = default;
403 
405  std::array<double, kCartDoF / 2> position = {};
406 
408  std::array<double, kCartDoF / 2> orientation = {};
409 
417  std::array<std::string, 2> ref_frame = {};
418 
423  std::array<double, kSerialJointDoF> ref_q = {};
424 
429  std::array<double, kMaxExtAxes> ref_q_e = {};
430 
432  std::string str() const;
433 };
434 
436 using FlexivDataTypes = std::variant<int, double, std::string, rdk::JPos, rdk::Coord,
437  std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
438  std::vector<rdk::Coord>>;
439 
447 std::ostream& operator<<(std::ostream& ostream, const RobotInfo& robot_info);
448 
456 std::ostream& operator<<(std::ostream& ostream, const RobotStates& robot_states);
457 
465 std::ostream& operator<<(std::ostream& ostream, const PlanInfo& plan_info);
466 
474 std::ostream& operator<<(std::ostream& ostream, const GripperStates& gripper_states);
475 
476 } /* namespace rdk */
477 } /* namespace flexiv */
478 
479 #endif /* FLEXIV_RDK_DATA_HPP_ */
CoordType
Type of commonly-used reference coordinates.
Definition: data.hpp:58
@ WORLD
World frame (fixed).
@ TCP
TCP frame (move with the robot's end effector).
constexpr size_t kMaxExtAxes
Definition: data.hpp:31
constexpr size_t kPoseSize
Definition: data.hpp:25
constexpr size_t kSerialJointDoF
Definition: data.hpp:22
constexpr size_t kCartDoF
Definition: data.hpp:19
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
Definition: data.hpp:39
@ 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:28
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:438
std::ostream & operator<<(std::ostream &ostream, const RobotInfo &robot_info)
Operator overloading to out stream all robot info in JSON format: {"info_1": [val1,...
Data structure representing the customized data type "COORD" in Flexiv Elements.
Definition: data.hpp:381
std::array< double, kCartDoF/2 > orientation
Definition: data.hpp:408
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={}, const std::array< double, kMaxExtAxes > &_ref_q_e={})
Construct an instance of Coord.
Definition: data.hpp:390
std::array< std::string, 2 > ref_frame
Definition: data.hpp:417
std::array< double, kCartDoF/2 > position
Definition: data.hpp:405
std::array< double, kSerialJointDoF > ref_q
Definition: data.hpp:423
std::array< double, kMaxExtAxes > ref_q_e
Definition: data.hpp:429
std::string str() const
Data structure containing the gripper states.
Definition: data.hpp:305
Data structure representing the customized data type "JPOS" in Flexiv Elements.
Definition: data.hpp:347
std::array< double, kSerialJointDoF > q
Definition: data.hpp:362
JPos(const std::array< double, kSerialJointDoF > &_q, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
Definition: data.hpp:353
std::string str() const
std::array< double, kMaxExtAxes > q_e
Definition: data.hpp:367
Data structure containing information of the on-going primitive/plan.
Definition: data.hpp:273
std::string node_name
Definition: data.hpp:278
std::string node_path_time_period
Definition: data.hpp:284
std::string node_path
Definition: data.hpp:281
std::string pt_name
Definition: data.hpp:275
double velocity_scale
Definition: data.hpp:293
std::string assigned_plan_name
Definition: data.hpp:290
std::string node_path_number
Definition: data.hpp:287
General information about the connected robot.
Definition: data.hpp:69
std::vector< double > tau_max
Definition: data.hpp:121
std::vector< double > q_max
Definition: data.hpp:109
std::string license_type
Definition: data.hpp:80
std::string serial_num
Definition: data.hpp:71
std::string software_ver
Definition: data.hpp:74
std::vector< double > dq_max
Definition: data.hpp:115
std::array< double, kCartDoF > K_x_nom
Definition: data.hpp:91
std::string model_name
Definition: data.hpp:77
std::vector< double > K_q_nom
Definition: data.hpp:97
std::vector< double > q_min
Definition: data.hpp:103
Data structure containing the joint- and Cartesian-space robot states.
Definition: data.hpp:130
std::array< double, kCartDoF > ft_sensor_raw
Definition: data.hpp:238
std::array< double, kCartDoF > ext_wrench_in_world
Definition: data.hpp:254
std::vector< double > dtheta
Definition: data.hpp:158
std::vector< double > q
Definition: data.hpp:136
std::vector< double > dq_e
Definition: data.hpp:195
std::vector< double > q_e
Definition: data.hpp:189
std::array< double, kCartDoF > ext_wrench_in_tcp
Definition: data.hpp:246
std::vector< double > tau_dot
Definition: data.hpp:176
std::array< double, kCartDoF > ext_wrench_in_tcp_raw
Definition: data.hpp:259
std::vector< double > tau_ext
Definition: data.hpp:183
std::array< double, kPoseSize > tcp_pose
Definition: data.hpp:208
std::vector< double > theta
Definition: data.hpp:144
std::vector< double > dq
Definition: data.hpp:151
std::array< double, kCartDoF > tcp_vel
Definition: data.hpp:223
std::vector< double > tau_des
Definition: data.hpp:170
std::array< double, kPoseSize > tcp_pose_des
Definition: data.hpp:215
std::array< double, kCartDoF > ext_wrench_in_world_raw
Definition: data.hpp:264
std::vector< double > tau
Definition: data.hpp:164
std::array< double, kPoseSize > flange_pose
Definition: data.hpp:230
std::vector< double > tau_e
Definition: data.hpp:201
Data structure containing robot tool parameters.
Definition: data.hpp:323
std::array< double, kPoseSize > tcp_location
Definition: data.hpp:336
std::array< double, 3 > CoM
Definition: data.hpp:328
std::array< double, 6 > inertia
Definition: data.hpp:331