Flexiv RDK APIs  1.4
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 
15 namespace flexiv {
16 namespace rdk {
17 
19 constexpr size_t kCartDoF = 6;
20 
22 constexpr size_t kPoseSize = 7;
23 
25 constexpr size_t kIOPorts = 16;
26 
31 struct RobotInfo
32 {
34  std::string serial_num = {};
35 
37  std::string software_ver = {};
38 
40  std::string model_name = {};
41 
43  size_t DoF = {};
44 
51  std::array<double, kCartDoF> K_x_nom = {};
52 
57  std::vector<double> K_q_nom = {};
58 
63  std::vector<double> q_min = {};
64 
69  std::vector<double> q_max = {};
70 
75  std::vector<double> dq_max = {};
76 
81  std::vector<double> tau_max = {};
82 };
83 
89 {
95  std::vector<double> q = {};
96 
103  std::vector<double> theta = {};
104 
110  std::vector<double> dq = {};
111 
117  std::vector<double> dtheta = {};
118 
122  std::vector<double> tau = {};
123 
128  std::vector<double> tau_des = {};
129 
134  std::vector<double> tau_dot = {};
135 
141  std::vector<double> tau_ext = {};
142 
148  std::array<double, kPoseSize> tcp_pose = {};
149 
155  std::array<double, kPoseSize> tcp_pose_des = {};
156 
163  std::array<double, kCartDoF> tcp_vel = {};
164 
170  std::array<double, kPoseSize> flange_pose = {};
171 
178  std::array<double, kCartDoF> ft_sensor_raw = {};
179 
186  std::array<double, kCartDoF> ext_wrench_in_tcp = {};
187 
194  std::array<double, kCartDoF> ext_wrench_in_world = {};
195 };
196 
201 struct PlanInfo
202 {
204  std::string pt_name = {};
205 
207  std::string node_name = {};
208 
210  std::string node_path = {};
211 
213  std::string node_path_time_period = {};
214 
216  std::string node_path_number = {};
217 
219  std::string assigned_plan_name = {};
220 
222  double velocity_scale = {};
223 
225  bool waiting_for_step = {};
226 };
227 
233 {
235  double width = {};
236 
239  double force = {};
240 
242  double max_width = {};
243 };
244 
250 {
252  double mass = 0.0;
253 
255  std::array<double, 3> CoM = {};
256 
258  std::array<double, 6> inertia = {};
259 
263  std::array<double, kPoseSize> tcp_location = {};
264 };
265 
273 std::ostream& operator<<(std::ostream& ostream, const RobotInfo& robot_info);
274 
282 std::ostream& operator<<(std::ostream& ostream, const RobotStates& robot_states);
283 
291 std::ostream& operator<<(std::ostream& ostream, const PlanInfo& plan_info);
292 
300 std::ostream& operator<<(std::ostream& ostream, const GripperStates& gripper_states);
301 
302 } /* namespace rdk */
303 } /* namespace flexiv */
304 
305 #endif /* FLEXIV_RDK_DATA_HPP_ */
constexpr size_t kPoseSize
Definition: data.hpp:22
constexpr size_t kCartDoF
Definition: data.hpp:19
constexpr size_t kIOPorts
Definition: data.hpp:25
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 containing the gripper states.
Definition: data.hpp:233
Data structure containing information of the on-going primitive/plan.
Definition: data.hpp:202
std::string node_name
Definition: data.hpp:207
std::string node_path_time_period
Definition: data.hpp:213
std::string node_path
Definition: data.hpp:210
std::string pt_name
Definition: data.hpp:204
double velocity_scale
Definition: data.hpp:222
std::string assigned_plan_name
Definition: data.hpp:219
std::string node_path_number
Definition: data.hpp:216
General information about the connected robot.
Definition: data.hpp:32
std::vector< double > tau_max
Definition: data.hpp:81
std::vector< double > q_max
Definition: data.hpp:69
std::string serial_num
Definition: data.hpp:34
std::string software_ver
Definition: data.hpp:37
std::vector< double > dq_max
Definition: data.hpp:75
std::array< double, kCartDoF > K_x_nom
Definition: data.hpp:51
std::string model_name
Definition: data.hpp:40
std::vector< double > K_q_nom
Definition: data.hpp:57
std::vector< double > q_min
Definition: data.hpp:63
Data structure containing the joint- and Cartesian-space robot states.
Definition: data.hpp:89
std::array< double, kCartDoF > ft_sensor_raw
Definition: data.hpp:178
std::array< double, kCartDoF > ext_wrench_in_world
Definition: data.hpp:194
std::vector< double > dtheta
Definition: data.hpp:117
std::vector< double > q
Definition: data.hpp:95
std::array< double, kCartDoF > ext_wrench_in_tcp
Definition: data.hpp:186
std::vector< double > tau_dot
Definition: data.hpp:134
std::vector< double > tau_ext
Definition: data.hpp:141
std::array< double, kPoseSize > tcp_pose
Definition: data.hpp:148
std::vector< double > theta
Definition: data.hpp:103
std::vector< double > dq
Definition: data.hpp:110
std::array< double, kCartDoF > tcp_vel
Definition: data.hpp:163
std::vector< double > tau_des
Definition: data.hpp:128
std::array< double, kPoseSize > tcp_pose_des
Definition: data.hpp:155
std::vector< double > tau
Definition: data.hpp:122
std::array< double, kPoseSize > flange_pose
Definition: data.hpp:170
Data structure containing robot tool parameters.
Definition: data.hpp:250
std::array< double, kPoseSize > tcp_location
Definition: data.hpp:263
std::array< double, 3 > CoM
Definition: data.hpp:255
std::array< double, 6 > inertia
Definition: data.hpp:258