Franky 0.12.0
A High-Level Motion API for Franka
|
Full state of the robot. More...
#include <robot_state.hpp>
Static Public Member Functions | |
static RobotState | from_franka (const franka::RobotState &robot_state, std::optional< Vector7d > ddq_est=std::nullopt, std::optional< Twist > O_dP_EE_est=std::nullopt, std::optional< TwistAcceleration > O_ddP_EE_est=std::nullopt, std::optional< double > delbow_est=std::nullopt, std::optional< double > ddelbow_est=std::nullopt) |
static RobotState | from_franka (const franka::RobotState &robot_state, const Jacobian &ee_jacobian, const Vector7d &ddq_est) |
Full state of the robot.
This class contains all fields of franka::RobotState and some additional fields. Each additional field ends in "_est". Unlike franka::RobotState, all fields are converted to appropriate Eigen/franky types.
|
static |
|
static |
Vector6d franky::RobotState::cartesian_collision {} |
Indicates which contact level is activated in which Cartesian dimension
Vector6d franky::RobotState::cartesian_contact {} |
Indicates which contact level is activated in which Cartesian dimension
double franky::RobotState::control_command_success_rate {} |
Percentage of the last 100 control commands that were successfully received by the robot.
Shows a value of zero if no control or motion generator loop is currently running.
Range:
franka::Errors franky::RobotState::current_errors {} |
Current error state.
double franky::RobotState::ddelbow_c {} |
Commanded elbow acceleration of the 3rd joint in
std::optional<double> franky::RobotState::ddelbow_est {} |
Estimated elbow acceleration (acceleration of the third joint), computed by franky. Not provided by franka firmware. Unit:
Vector7d franky::RobotState::ddq_d {} |
std::optional<Vector7d> franky::RobotState::ddq_est {} |
Estimated joint acceleration computed by franky. This value does not come from the franka firmware. Unit:
double franky::RobotState::delbow_c {} |
Commanded velocity of the 3rd joint in
std::optional<double> franky::RobotState::delbow_est {} |
Estimated elbow velocity (velocity of the third joint), computed by franky. Not provided by franka firmware. Unit:
Vector7d franky::RobotState::dq {} |
Vector7d franky::RobotState::dq_d {} |
Vector7d franky::RobotState::dtau_J {} |
Vector7d franky::RobotState::dtheta {} |
ElbowState franky::RobotState::elbow {} |
Elbow configuration.
ElbowState franky::RobotState::elbow_c {} |
Commanded elbow configuration.
ElbowState franky::RobotState::elbow_d {} |
Desired elbow configuration.
Affine franky::RobotState::F_T_EE {} |
Eigen::Vector3d franky::RobotState::F_x_Cee {} |
Eigen::Vector3d franky::RobotState::F_x_Cload {} |
Eigen::Vector3d franky::RobotState::F_x_Ctotal {} |
IntertiaMatrix franky::RobotState::I_ee {} |
IntertiaMatrix franky::RobotState::I_load {} |
IntertiaMatrix franky::RobotState::I_total {} |
Vector7d franky::RobotState::joint_collision {} |
Indicates which contact level is activated in which joint. After contact disappears, the value stays the same until a reset command is sent.
Vector7d franky::RobotState::joint_contact {} |
Indicates which contact level is activated in which joint. After contact disappears, value turns to zero.
Vector6d franky::RobotState::K_F_ext_hat_K {} |
franka::Errors franky::RobotState::last_motion_errors {} |
Contains the errors that aborted the previous motion.
double franky::RobotState::m_ee {} |
double franky::RobotState::m_load {} |
double franky::RobotState::m_total {} |
TwistAcceleration franky::RobotState::O_ddP_EE_c {} |
std::optional<TwistAcceleration> franky::RobotState::O_ddP_EE_est {} |
Estimated end-effector spatial acceleration (linear and angular acceleration) expressed in base frame. Computed by franky; not provided by franka firmware. Unit:
Twist franky::RobotState::O_dP_EE_c {} |
Twist franky::RobotState::O_dP_EE_d {} |
std::optional<Twist> franky::RobotState::O_dP_EE_est {} |
Estimated end-effector twist (linear and angular velocity) expressed in base frame. Computed by franky; not provided by franka firmware. Unit:
Vector6d franky::RobotState::O_F_ext_hat_K {} |
Affine franky::RobotState::O_T_EE {} |
Affine franky::RobotState::O_T_EE_c {} |
Affine franky::RobotState::O_T_EE_d {} |
Vector7d franky::RobotState::q {} |
Vector7d franky::RobotState::q_d {} |
franka::RobotMode franky::RobotState::robot_mode = franka::RobotMode::kUserStopped |
Current robot mode.
Vector7d franky::RobotState::tau_ext_hat_filtered {} |
Vector7d franky::RobotState::tau_J {} |
Vector7d franky::RobotState::tau_J_d {} |
Vector7d franky::RobotState::theta {} |
franka::Duration franky::RobotState::time {} |
Strictly monotonically increasing timestamp since robot start.
Inside of control loops time_step parameter of Robot::control can be used instead.