7 #ifndef FLEXIV_RDK_DATA_HPP_ 
    8 #define FLEXIV_RDK_DATA_HPP_ 
   99     std::chrono::time_point<std::chrono::system_clock> 
timestamp;
 
  178     std::vector<double> 
q = {};
 
  195     std::vector<double> 
dq = {};
 
  210     std::vector<double> 
tau = {};
 
  352     JPos(
const std::array<double, kSerialJointDoF>& _q_m,
 
  353         const std::array<double, kMaxExtAxes>& _q_e = {})
 
  361     std::array<double, kSerialJointDoF> 
q_m = {};
 
  366     std::array<double, kMaxExtAxes> 
q_e = {};
 
  389     Coord(
const std::array<double, kCartDoF / 2>& _position,
 
  390         const std::array<double, kCartDoF / 2>& _orientation,
 
  391         const std::array<std::string, 2>& _ref_frame,
 
  392         const std::array<double, kSerialJointDoF>& _ref_q_m = {},
 
  393         const std::array<double, kMaxExtAxes>& _ref_q_e = {})
 
  422     std::array<double, kSerialJointDoF> 
ref_q_m = {};
 
  436     std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
 
  437     std::vector<rdk::Coord>>;
 
CoordType
Type of commonly-used reference coordinates.
 
@ 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
 
constexpr size_t kPoseSize
 
constexpr size_t kSerialJointDoF
 
constexpr size_t kCartDoF
 
OperationalStatus
Operational status of the robot. Except for the first two, the other enumerators indicate the cause o...
 
@ 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
 
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
 
Data structure representing the customized data type "COORD" in Flexiv Elements.
 
std::array< double, kCartDoF/2 > orientation
 
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.
 
std::array< std::string, 2 > ref_frame
 
std::array< double, kCartDoF/2 > position
 
std::array< double, kSerialJointDoF > ref_q_m
 
std::array< double, kMaxExtAxes > ref_q_e
 
Data structure representing the customized data type "JPOS" in Flexiv Elements.
 
JPos(const std::array< double, kSerialJointDoF > &_q_m, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
 
std::array< double, kMaxExtAxes > q_e
 
std::array< double, kSerialJointDoF > q_m
 
Information of the on-going primitive/plan.
 
std::string node_path_time_period
 
std::string assigned_plan_name
 
std::string node_path_number
 
Information about a robot event.
 
std::string probable_causes
 
std::chrono::time_point< std::chrono::system_clock > timestamp
 
std::string recommended_actions
 
General information about the connected robot.
 
std::vector< double > tau_max
 
std::vector< double > q_max
 
std::vector< double > dq_max
 
std::array< double, kCartDoF > K_x_nom
 
std::vector< double > K_q_nom
 
std::vector< double > q_min
 
Robot states data in joint and Cartesian space.
 
std::array< double, kCartDoF > ft_sensor_raw
 
std::array< double, kCartDoF > ext_wrench_in_world
 
std::vector< double > dtheta
 
std::pair< int, int > timestamp
 
std::vector< double > temperature
 
std::array< double, kCartDoF > ext_wrench_in_tcp
 
std::vector< double > tau_dot
 
std::array< double, kCartDoF > ext_wrench_in_tcp_raw
 
std::vector< double > tau_ext
 
std::array< double, kPoseSize > tcp_pose
 
std::vector< double > theta
 
std::array< double, kCartDoF > tcp_vel
 
std::vector< double > tau_des
 
std::array< double, kCartDoF > ext_wrench_in_world_raw
 
std::vector< double > tau
 
std::vector< double > tau_interact
 
std::array< double, kPoseSize > flange_pose