Flexiv RDK APIs  1.5.1
Public Attributes | List of all members
flexiv::rdk::RobotStates Struct Reference

Data structure containing the joint- and Cartesian-space robot states. More...

#include <data.hpp>

Public Attributes

std::vector< double > q = {}
 
std::vector< double > theta = {}
 
std::vector< double > dq = {}
 
std::vector< double > dtheta = {}
 
std::vector< double > tau = {}
 
std::vector< double > tau_des = {}
 
std::vector< double > tau_dot = {}
 
std::vector< double > tau_ext = {}
 
std::vector< double > q_e = {}
 
std::vector< double > dq_e = {}
 
std::vector< double > tau_e = {}
 
std::array< double, kPoseSize > tcp_pose = {}
 
std::array< double, kPoseSize > tcp_pose_des = {}
 
std::array< double, kCartDoF > tcp_vel = {}
 
std::array< double, kPoseSize > flange_pose = {}
 
std::array< double, kCartDoF > ft_sensor_raw = {}
 
std::array< double, kCartDoF > ext_wrench_in_tcp = {}
 
std::array< double, kCartDoF > ext_wrench_in_world = {}
 
std::array< double, kCartDoF > ext_wrench_in_tcp_raw = {}
 
std::array< double, kCartDoF > ext_wrench_in_world_raw = {}
 

Detailed Description

Data structure containing the joint- and Cartesian-space robot states.

See also
Robot::states().

Definition at line 129 of file data.hpp.

Member Data Documentation

◆ dq

std::vector<double> flexiv::rdk::RobotStates::dq = {}

Measured joint velocities of the arm 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] \).

Definition at line 151 of file data.hpp.

◆ dq_e

std::vector<double> flexiv::rdk::RobotStates::dq_e = {}

Measured joint velocities of the external axes (if any): \( \dot{q}_e \in \mathbb{R}^{n_e \times 1} \). Unit: \( [rad/s] \).

Definition at line 195 of file data.hpp.

◆ dtheta

std::vector<double> flexiv::rdk::RobotStates::dtheta = {}

Measured joint velocities of the arm using motor-side encoder: \( \dot{\theta} \in \mathbb{R}^{n \times 1} \). This is the indirect but less noisy measurement of joint velocities, preferred for most cases. Unit: \( [rad/s] \).

Definition at line 158 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 246 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 259 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 254 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 264 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 230 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 238 of file data.hpp.

◆ q

std::vector<double> flexiv::rdk::RobotStates::q = {}

Measured joint positions of the arm using link-side encoder: \( q \in \mathbb{R}^{n \times 1} \). This is the direct measurement of joint positions, preferred for most cases. Unit: \( [rad] \).

Definition at line 136 of file data.hpp.

◆ q_e

std::vector<double> flexiv::rdk::RobotStates::q_e = {}

Measured joint positions of the external axes (if any): \( q_e \in \mathbb{R}^{n_e \times 1} \). Unit: \( [rad] \).

Definition at line 189 of file data.hpp.

◆ tau

std::vector<double> flexiv::rdk::RobotStates::tau = {}

Measured joint torques of the arm: \( \tau \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm] \).

Definition at line 164 of file data.hpp.

◆ tau_des

std::vector<double> flexiv::rdk::RobotStates::tau_des = {}

Desired joint torques of the arm: \( \tau_{d} \in \mathbb{R}^{n \times 1} \). Compensation of nonlinear dynamics (gravity, centrifugal, and Coriolis) is excluded. Unit: \( [Nm] \).

Definition at line 170 of file data.hpp.

◆ tau_dot

std::vector<double> flexiv::rdk::RobotStates::tau_dot = {}

Numerical derivative of measured joint torques of the arm: \( \dot{\tau} \in \mathbb{R}^{n \times 1} \). Unit: \( [Nm/s] \).

Definition at line 176 of file data.hpp.

◆ tau_e

std::vector<double> flexiv::rdk::RobotStates::tau_e = {}

Measured joint torques of the external axes (if any): \( \tau_e \in \mathbb{R}^{n_e \times 1} \). Unit: \( [Nm] \).

Definition at line 201 of file data.hpp.

◆ tau_ext

std::vector<double> flexiv::rdk::RobotStates::tau_ext = {}

Estimated external joint torques of the arm: \( \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] \).

Definition at line 183 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 208 of file data.hpp.

◆ tcp_pose_des

std::array<double, kPoseSize> flexiv::rdk::RobotStates::tcp_pose_des = {}

Desired TCP pose expressed in world frame: \( {^{O}T_{TCP}}_{d} \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 215 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 223 of file data.hpp.

◆ theta

std::vector<double> flexiv::rdk::RobotStates::theta = {}

Measured joint positions of the arm 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] \).

Definition at line 144 of file data.hpp.


The documentation for this struct was generated from the following file: