Skip to content
Snippets Groups Projects

Package fr3_impedance_controller_real in nix env

Merged Kevin Haninger requested to merge 7-add-local-package-to-nix-flake-new into main
1 unresolved thread
Compare and Show latest version
5 files
+ 161
114
Compare changes
  • Side-by-side
  • Inline
Files
5
@@ -10,21 +10,23 @@ private:
Vec6<T> x_0e_err_; // end-effector 6-DoF pose error
Vec6<T> x_0e_err_prev_; // previous error
Mat6<T> K_task_; // task-space stiffness matrix
Mat6<T> B_task_; // task-space damping matrix
Mat6<T> D_task_; // task-space damping matrix
Vec6<T> F_task_; // computed task-space wrench from impedance controller
Vec7<T> tau_task_; // joint-spce impedance torque
Vec7<T> q_null_err_; // null-space joint configuration error
Vec7<T> q_null_err_prev_; // previous error
Mat7<T> K_null_; // null-space stiffness matrix
Mat7<T> B_null_; // null-space damping matrix
Mat7<T> D_null_; // null-space damping matrix
Vec7<T> tau_null_; // computed null-space torque from impedance controller
public:
ImpedanceController(const Mat6<T> & K_task, const Mat6<T> & B_task, const Mat7<T> & K_null,
const Mat7<T> & B_null);
ImpedanceController();
//* ----- SETTERS --------------------------------------------------------------------------------
void set_parameters(const Mat6<T> & K_task, const Mat6<T> & D_task, //
const Mat7<T> & K_null, const Mat7<T> & D_null);
//* ----- METHODS ---------------------------------------------------------------------------- *//
//* ----- METHODS --------------------------------------------------------------------------------
/**
* @param q_null_des : desired null-space joint configuration
* @param q_null_mes : measured null-space joint configuration
@@ -36,7 +38,7 @@ public:
x_0e_err_prev_ = x_0e_err_;
};
//* ----- GETTERS ---------------------------------------------------------------------------- *//
//* ----- GETTERS --------------------------------------------------------------------------------
/**
* @param dt : timestep
* @param p_0e_des : desired end-effector position in {W} frame
@@ -61,7 +63,7 @@ public:
Vec7<T> get_null_impedance_torque(const Vec7<T> & dq_null_err, const Eigen::MatrixXd & J,
const Eigen::MatrixXd & Jt_pinv);
//* ----- PRINTER ---------------------------------------------------------------------------- *//
//* ----- PRINTER --------------------------------------------------------------------------------
void print_pose_error();
void print_impedance_torque();
};
Loading