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
2 files
+ 67
44
Compare changes
  • Side-by-side
  • Inline
Files
2
@@ -122,7 +122,7 @@ private:
Mat6<double> D_task_, D_task_target_;
Mat7<double> K_null_, K_null_target_;
Mat7<double> D_null_, D_null_target_;
Eigen::Matrix<double, 7, 1> q_d_nullspace_;
// Eigen::Matrix<double, 7, 1> q_d_nullspace_;
//* ----- Control States -------------------------------------------------------------------------
/* Robot Model */
@@ -138,6 +138,7 @@ private:
/* Joint states */
Vec7<double> q_mes_;
Vec7<double> q_null_des_;
Vec7<double> dq_mes_, dq_mes_prev_;
Vec7<double> ddq_eul_, ddq_eul_prev_; // joint accel obtained by backward Euler method
Vec7<double> h_mes_, h_mes_prev_; // General Momentum
@@ -187,13 +188,13 @@ private:
// const std::vector<double> fric_phi3{ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
public:
//* ----- SUBSCRIBE CALLBACK FUNC ----------------------------------------------------------------
//* ----- SUBSCRIBE CALLBACK ---------------------------------------------------------------------
void subscribe_target_twist(const geometry_msgs::TwistConstPtr & msg);
void subscribe_joy_command(const sensor_msgs::JoyConstPtr & msg);
void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr & msg);
//* ----- PARAMETER SERVER CALLBACK FUNC ---------------------------------------------------------
//* ----- PARAMETER SERVER CALLBACK --------------------------------------------------------------
void complianceParamCallback(franka_example_controllers::compliance_paramConfig & config,
uint32_t level);
Loading