Flexiv RDK APIs  0.10
Data.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIVRDK_DATA_HPP_
7 #define FLEXIVRDK_DATA_HPP_
8 
9 #include <vector>
10 #include <string>
11 #include <ostream>
12 
13 namespace flexiv {
14 
16 constexpr size_t k_IOPorts = 16;
17 
22 struct RobotInfo
23 {
25  std::string serialNum = {};
26 
28  unsigned int DOF = {};
29 
31  std::string softwareVer = {};
32 
40  std::vector<double> nominalK = {};
41 
46  std::vector<double> qHome = {};
47 
52  std::vector<double> qMin = {};
53 
58  std::vector<double> qMax = {};
59 
64  std::vector<double> dqMax = {};
65 
70  std::vector<double> tauMax = {};
71 };
72 
78 {
84  std::vector<double> q = {};
85 
92  std::vector<double> theta = {};
93 
99  std::vector<double> dq = {};
100 
107  std::vector<double> dtheta = {};
108 
113  std::vector<double> tau = {};
114 
120  std::vector<double> tauDes = {};
121 
126  std::vector<double> tauDot = {};
127 
134  std::vector<double> tauExt = {};
135 
142  std::vector<double> tcpPose = {};
143 
150  std::vector<double> tcpPoseDes = {};
151 
159  std::vector<double> tcpVel = {};
160 
167  std::vector<double> camPose = {};
168 
175  std::vector<double> flangePose = {};
176 
184  std::vector<double> ftSensorRaw = {};
185 
192  std::vector<double> extWrenchInTcp = {};
193 
200  std::vector<double> extWrenchInBase = {};
201 };
202 
207 struct PlanInfo
208 {
210  std::string ptName = {};
211 
213  std::string nodeName = {};
214 
216  std::string nodePath = {};
217 
219  std::string nodePathTimePeriod = {};
220 
222  std::string nodePathNumber = {};
223 
225  std::string assignedPlanName = {};
226 
228  double velocityScale = {};
229 };
230 
236 {
238  double width = {};
239 
242  double force = {};
243 
245  double maxWidth = {};
246 
248  bool isMoving = {};
249 };
250 
258 std::ostream& operator<<(
259  std::ostream& ostream, const flexiv::RobotInfo& robotInfo);
260 
268 std::ostream& operator<<(
269  std::ostream& ostream, const flexiv::RobotStates& robotStates);
270 
278 std::ostream& operator<<(
279  std::ostream& ostream, const flexiv::PlanInfo& planInfo);
280 
288 std::ostream& operator<<(
289  std::ostream& ostream, const flexiv::GripperStates& gripperStates);
290 
291 } /* namespace flexiv */
292 
293 #endif /* FLEXIVRDK_DATA_HPP_ */
std::ostream & operator<<(std::ostream &ostream, const flexiv::RobotInfo &robotInfo)
Operator overloading to out stream all robot info in JSON format: {"info_1": [val1,...
constexpr size_t k_IOPorts
Definition: Data.hpp:16
Data struct containing the gripper states.
Definition: Data.hpp:236
Data struct containing information of the on-going primitive/plan.
Definition: Data.hpp:208
std::string nodePath
Definition: Data.hpp:216
std::string ptName
Definition: Data.hpp:210
std::string assignedPlanName
Definition: Data.hpp:225
std::string nodeName
Definition: Data.hpp:213
std::string nodePathNumber
Definition: Data.hpp:222
std::string nodePathTimePeriod
Definition: Data.hpp:219
double velocityScale
Definition: Data.hpp:228
General information of the connected robot.
Definition: Data.hpp:23
std::vector< double > tauMax
Definition: Data.hpp:70
std::vector< double > qMin
Definition: Data.hpp:52
unsigned int DOF
Definition: Data.hpp:28
std::string softwareVer
Definition: Data.hpp:31
std::vector< double > qHome
Definition: Data.hpp:46
std::vector< double > qMax
Definition: Data.hpp:58
std::string serialNum
Definition: Data.hpp:25
std::vector< double > dqMax
Definition: Data.hpp:64
std::vector< double > nominalK
Definition: Data.hpp:40
Data struct containing the joint- and Cartesian-space robot states.
Definition: Data.hpp:78
std::vector< double > q
Definition: Data.hpp:84
std::vector< double > tcpPoseDes
Definition: Data.hpp:150
std::vector< double > dq
Definition: Data.hpp:99
std::vector< double > tauDes
Definition: Data.hpp:120
std::vector< double > ftSensorRaw
Definition: Data.hpp:184
std::vector< double > flangePose
Definition: Data.hpp:175
std::vector< double > dtheta
Definition: Data.hpp:107
std::vector< double > extWrenchInTcp
Definition: Data.hpp:192
std::vector< double > tauExt
Definition: Data.hpp:134
std::vector< double > tau
Definition: Data.hpp:113
std::vector< double > theta
Definition: Data.hpp:92
std::vector< double > tcpPose
Definition: Data.hpp:142
std::vector< double > tcpVel
Definition: Data.hpp:159
std::vector< double > extWrenchInBase
Definition: Data.hpp:200
std::vector< double > tauDot
Definition: Data.hpp:126
std::vector< double > camPose
Definition: Data.hpp:167