7 #ifndef FLEXIV_RDK_DATA_HPP_
8 #define FLEXIV_RDK_DATA_HPP_
91 std::array<double, kCartDoF>
K_x_nom = {};
136 std::vector<double>
q = {};
151 std::vector<double>
dq = {};
164 std::vector<double>
tau = {};
189 std::vector<double>
q_e = {};
328 std::array<double, 3>
CoM = {};
353 JPos(
const std::array<double, kSerialJointDoF>& _q,
354 const std::array<double, kMaxExtAxes>& _q_e = {})
362 std::array<double, kSerialJointDoF>
q = {};
367 std::array<double, kMaxExtAxes>
q_e = {};
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 = {})
423 std::array<double, kSerialJointDoF>
ref_q = {};
437 std::vector<int>, std::vector<double>, std::vector<std::string>, std::vector<rdk::JPos>,
438 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).
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
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.
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={}, 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
std::array< double, kMaxExtAxes > ref_q_e
Data structure containing the gripper states.
Data structure representing the customized data type "JPOS" in Flexiv Elements.
std::array< double, kSerialJointDoF > q
JPos(const std::array< double, kSerialJointDoF > &_q, const std::array< double, kMaxExtAxes > &_q_e={})
Construct an instance of JPos.
std::array< double, kMaxExtAxes > q_e
Data structure containing information of the on-going primitive/plan.
std::string node_path_time_period
std::string assigned_plan_name
std::string node_path_number
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
Data structure containing the joint- and Cartesian-space robot states.
std::array< double, kCartDoF > ft_sensor_raw
std::array< double, kCartDoF > ext_wrench_in_world
std::vector< double > dtheta
std::vector< double > dq_e
std::vector< double > q_e
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, kPoseSize > tcp_pose_des
std::array< double, kCartDoF > ext_wrench_in_world_raw
std::vector< double > tau
std::array< double, kPoseSize > flange_pose
std::vector< double > tau_e