Robot states data in joint- and Cartesian-space.
More...
#include <data.hpp>
Robot states data in joint- and Cartesian-space.
- See also
- Robot::states().
Definition at line 175 of file data.hpp.
◆ dq
std::vector<double> flexiv::rdk::RobotStates::dq = {} |
Measured joint velocities of the full system using link-side encoder: \( \dot{q} \in \mathbb{R}^{n \times 1} \). This is the direct but more noisy measurement of joint velocities. Unit: \( [rad/s] or [m/s] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has only one encoder, then \( \dot{\theta} = \dot{q} \).
Definition at line 202 of file data.hpp.
◆ dtheta
std::vector<double> flexiv::rdk::RobotStates::dtheta = {} |
Measured joint velocities of the full system using motor-side encoder: \( \dot{\theta} \in \mathbb{R}^{n \times 1} \). This is the indirect but less noisy measurement of joint velocities. Unit: \( [rad/s] or [m/s] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has only one encoder, then \( \dot{\theta} = \dot{q} \).
Definition at line 211 of file data.hpp.
◆ ext_wrench_in_tcp
std::array<double, kCartDoF> flexiv::rdk::RobotStates::ext_wrench_in_tcp = {} |
Estimated external wrench applied on TCP and expressed in TCP frame: \( ^{TCP}F_{ext} \in \mathbb{R}^{6 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) force and \( \mathbb{R}^{3 \times 1} \) moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]:[Nm] \).
Definition at line 283 of file data.hpp.
◆ ext_wrench_in_tcp_raw
std::array<double, kCartDoF> flexiv::rdk::RobotStates::ext_wrench_in_tcp_raw = {} |
Unfiltered version of ext_wrench_in_tcp. The data is more noisy but has no filter latency.
Definition at line 296 of file data.hpp.
◆ ext_wrench_in_world
std::array<double, kCartDoF> flexiv::rdk::RobotStates::ext_wrench_in_world = {} |
Estimated external wrench applied on TCP and expressed in world frame: \( ^{0}F_{ext} \in \mathbb{R}^{6 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) force and \( \mathbb{R}^{3 \times 1} \) moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]:[Nm] \).
Definition at line 291 of file data.hpp.
◆ ext_wrench_in_world_raw
std::array<double, kCartDoF> flexiv::rdk::RobotStates::ext_wrench_in_world_raw = {} |
Unfiltered version of ext_wrench_in_world The data is more noisy but has no filter latency.
Definition at line 301 of file data.hpp.
◆ flange_pose
std::array<double, kPoseSize> flexiv::rdk::RobotStates::flange_pose = {} |
Measured flange pose expressed in world frame: \( ^{O}T_{flange} \in \mathbb{R}^{7 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) position and \( \mathbb{R}^{4 \times 1} \) quaternion: \( [x, y, z, q_w, q_x, q_y, q_z]^T \). Unit: \( [m]:[] \).
Definition at line 267 of file data.hpp.
◆ ft_sensor_raw
std::array<double, kCartDoF> flexiv::rdk::RobotStates::ft_sensor_raw = {} |
Force-torque (FT) sensor raw reading in flange frame: \( ^{flange}F_{raw} \in \mathbb{R}^{6 \times 1} \). The value is 0 if no FT sensor is installed. Consists of \( \mathbb{R}^{3 \times 1} \) force and \( \mathbb{R}^{3 \times 1} \) moment: \( [f_x, f_y, f_z, m_x, m_y, m_z]^T \). Unit: \( [N]:[Nm] \).
Definition at line 275 of file data.hpp.
std::vector<double> flexiv::rdk::RobotStates::q = {} |
Measured joint positions of the full system using link-side encoder: \( q \in \mathbb{R}^{n \times 1} \). This is the direct measurement of joint positions. Unit: \( [rad] or [m] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has only one encoder, then \( \theta = q \).
Definition at line 183 of file data.hpp.
◆ tau
std::vector<double> flexiv::rdk::RobotStates::tau = {} |
Measured joint torques of the full system: \( \tau \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has no torque measurement, then the corresponding value will be 0.
Definition at line 219 of file data.hpp.
◆ tau_des
std::vector<double> flexiv::rdk::RobotStates::tau_des = {} |
Desired joint torques of the full system: \( \tau_{d} \in \mathbb{R}^{n \times 1} \). Compensation of nonlinear dynamics (gravity, centrifugal, and Coriolis) is excluded. Unit: \( [Nm] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has no torque control capability, then the corresponding value will be 0.
Definition at line 228 of file data.hpp.
◆ tau_dot
std::vector<double> flexiv::rdk::RobotStates::tau_dot = {} |
Numerical derivative of measured joint torques of the full system: \( \dot{\tau} \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm/s] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has no torque measurement, then the corresponding value will be 0.
Definition at line 236 of file data.hpp.
◆ tau_ext
std::vector<double> flexiv::rdk::RobotStates::tau_ext = {} |
Estimated external joint torques of the full system: \( \hat \tau_{ext} \in \mathbb{R}^{n \times 1} \). Produced by any external contact (with robot body or end-effector) that does not belong to the known robot model. Unit: \( [Nm] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has no torque measurement, then the corresponding value will be 0.
Definition at line 245 of file data.hpp.
◆ tcp_pose
std::array<double, kPoseSize> flexiv::rdk::RobotStates::tcp_pose = {} |
Measured TCP pose expressed in world frame: \( ^{O}T_{TCP} \in \mathbb{R}^{7 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) position and \( \mathbb{R}^{4 \times 1} \) quaternion: \( [x, y, z, q_w, q_x, q_y, q_z]^T \). Unit: \( [m]:[] \).
Definition at line 252 of file data.hpp.
◆ tcp_vel
std::array<double, kCartDoF> flexiv::rdk::RobotStates::tcp_vel = {} |
Measured TCP velocity expressed in world frame: \( ^{O}\dot{X} \in \mathbb{R}^{6 \times 1} \). Consists of \( \mathbb{R}^{3 \times 1} \) linear velocity and \( \mathbb{R}^{3 \times 1} \) angular velocity: \( [v_x, v_y, v_z, \omega_x, \omega_y, \omega_z]^T \). Unit: \( [m/s]:[rad/s] \).
Definition at line 260 of file data.hpp.
◆ theta
std::vector<double> flexiv::rdk::RobotStates::theta = {} |
Measured joint positions of the full system using motor-side encoder: \( \theta \in \mathbb{R}^{n \times 1} \). This is the indirect measurement of joint positions. \( \theta = q + \Delta \), where \( \Delta \) is the joint's internal deflection between motor and link. Unit: \( [rad] or [m] \).
- Note
- This contains values for both the external axes (if any) and the robot manipulator.
-
If a joint has only one encoder, then \( \theta = q \).
Definition at line 193 of file data.hpp.
The documentation for this struct was generated from the following file: