6 #ifndef FLEXIVRDK_DATA_HPP_
7 #define FLEXIVRDK_DATA_HPP_
28 unsigned int DOF = {};
52 std::vector<double>
qMin = {};
58 std::vector<double>
qMax = {};
84 std::vector<double>
q = {};
99 std::vector<double>
dq = {};
113 std::vector<double>
tau = {};
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
Data struct containing the gripper states.
Data struct containing information of the on-going primitive/plan.
std::string assignedPlanName
std::string nodePathNumber
std::string nodePathTimePeriod
General information of the connected robot.
std::vector< double > tauMax
std::vector< double > qMin
std::vector< double > qHome
std::vector< double > qMax
std::vector< double > dqMax
std::vector< double > nominalK
Data struct containing the joint- and Cartesian-space robot states.
std::vector< double > tcpPoseDes
std::vector< double > tauDes
std::vector< double > ftSensorRaw
std::vector< double > flangePose
std::vector< double > dtheta
std::vector< double > extWrenchInTcp
std::vector< double > tauExt
std::vector< double > tau
std::vector< double > theta
std::vector< double > tcpPose
std::vector< double > tcpVel
std::vector< double > extWrenchInBase
std::vector< double > tauDot
std::vector< double > camPose