7 #ifndef FLEXIV_RDK_DATA_HPP_
8 #define FLEXIV_RDK_DATA_HPP_
51 std::array<double, kCartDoF>
K_x_nom = {};
95 std::vector<double>
q = {};
110 std::vector<double>
dq = {};
122 std::vector<double>
tau = {};
255 std::array<double, 3>
CoM = {};
constexpr size_t kPoseSize
constexpr size_t kCartDoF
constexpr size_t kIOPorts
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.
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::array< double, kCartDoF > ext_wrench_in_tcp
std::vector< double > tau_dot
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::vector< double > tau
std::array< double, kPoseSize > flange_pose