5#include <franka/robot_state.h>
25 const franka::RobotState &
robot_state, std::optional<Vector7d>
q_est = std::nullopt,
26 std::optional<Vector7d>
dq_est = std::nullopt, std::optional<Vector7d>
ddq_est = std::nullopt,
368 franka::RobotMode
robot_mode = franka::RobotMode::kUserStopped;
Elbow state of the robot.
Definition elbow_state.hpp:24
TwistAcceleration acceleration of a frame (2nd derivative of a pose).
Definition twist_acceleration.hpp:14
Twist of a frame.
Definition twist.hpp:13
Definition dynamics_limit.cpp:8
std::array< double, dims > toStdD(const Eigen::Matrix< double, dims, 1 > &vector)
Definition util.hpp:18
Eigen::Matrix< double, 3, 3 > IntertiaMatrix
Definition types.hpp:13
Eigen::Vector< double, 7 > Vector7d
Definition types.hpp:11
Eigen::Vector< double, 6 > Vector6d
Definition types.hpp:10
Eigen::Matrix< double, 6, 7 > Jacobian
Definition types.hpp:12
Eigen::Affine3d Affine
Definition types.hpp:15
Full state of the robot.
Definition robot_state.hpp:23
franka::Errors last_motion_errors
Definition robot_state.hpp:352
Affine O_T_EE
Definition robot_state.hpp:38
Vector6d K_F_ext_hat_K
Definition robot_state.hpp:289
Vector7d tau_ext_hat_filtered
Definition robot_state.hpp:267
static RobotState from_franka(const franka::RobotState &robot_state, std::optional< Vector7d > q_est=std::nullopt, std::optional< Vector7d > dq_est=std::nullopt, 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)
Definition robot_state.cpp:7
Vector7d joint_contact
Definition robot_state.hpp:229
Eigen::Vector3d F_x_Cee
Definition robot_state.hpp:106
std::optional< Vector7d > q_est
Definition robot_state.hpp:382
Eigen::Vector3d F_x_Ctotal
Definition robot_state.hpp:146
Vector7d dq_d
Definition robot_state.hpp:215
TwistAcceleration O_ddP_EE_c
Definition robot_state.hpp:330
std::optional< TwistAcceleration > O_ddP_EE_est
Definition robot_state.hpp:411
double delbow_c
Definition robot_state.hpp:166
Vector6d cartesian_contact
Definition robot_state.hpp:237
Affine EE_T_K
Definition robot_state.hpp:86
IntertiaMatrix I_total
Definition robot_state.hpp:139
Vector7d tau_J_d
Definition robot_state.hpp:184
ElbowState elbow_c
Definition robot_state.hpp:161
Vector7d joint_collision
Definition robot_state.hpp:247
Vector7d dtau_J
Definition robot_state.hpp:191
Vector6d cartesian_collision
Definition robot_state.hpp:258
Vector7d dtheta
Definition robot_state.hpp:342
Vector7d theta
Definition robot_state.hpp:336
double m_total
Definition robot_state.hpp:132
IntertiaMatrix I_ee
Definition robot_state.hpp:99
Affine O_T_EE_d
Definition robot_state.hpp:45
franka::Duration time
Definition robot_state.hpp:376
double control_command_success_rate
Definition robot_state.hpp:363
std::optional< Twist > O_dP_EE_est
Definition robot_state.hpp:402
Vector7d tau_J
Definition robot_state.hpp:177
Affine F_T_EE
Definition robot_state.hpp:55
std::optional< Vector7d > ddq_est
Definition robot_state.hpp:394
Twist O_dP_EE_d
Definition robot_state.hpp:297
double m_ee
Definition robot_state.hpp:92
Twist O_dP_EE_c
Definition robot_state.hpp:322
ElbowState elbow_d
Definition robot_state.hpp:156
ElbowState elbow
Definition robot_state.hpp:151
Vector7d ddq_d
Definition robot_state.hpp:221
Vector7d q_d
Definition robot_state.hpp:203
std::optional< Vector7d > dq_est
Definition robot_state.hpp:388
franka::RobotMode robot_mode
Definition robot_state.hpp:368
double ddelbow_c
Definition robot_state.hpp:171
Eigen::Vector3d F_x_Cload
Definition robot_state.hpp:126
double m_load
Definition robot_state.hpp:112
Vector6d O_F_ext_hat_K
Definition robot_state.hpp:278
std::optional< double > delbow_est
Definition robot_state.hpp:418
IntertiaMatrix I_load
Definition robot_state.hpp:119
Vector7d q
Definition robot_state.hpp:197
std::optional< double > ddelbow_est
Definition robot_state.hpp:424
Vector7d dq
Definition robot_state.hpp:209
Affine O_T_EE_c
Definition robot_state.hpp:316
franka::Errors current_errors
Definition robot_state.hpp:347