10 #include <dynamic_reconfigure/server.h> 11 #include <geometry_msgs/PoseStamped.h> 16 #include <Eigen/Dense> 18 #include <franka_example_controllers/compliance_paramConfig.h> 25 franka_hw::FrankaModelInterface,
26 hardware_interface::EffortJointInterface,
27 franka_hw::FrankaStateInterface> {
36 const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
37 const Eigen::Matrix<double, 7, 1>& tau_J_d);
58 std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>
ros::NodeHandle dynamic_reconfigure_compliance_param_node_
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle_
ros::Subscriber sub_equilibrium_pose_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
void starting(const ros::Time &) override
void update(const ros::Time &, const ros::Duration &period) override
Eigen::Vector3d position_d_target_
Eigen::Matrix< double, 7, 1 > q_d_nullspace_
Eigen::Matrix< double, 6, 6 > cartesian_damping_target_
double nullspace_stiffness_target_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Eigen::Quaterniond orientation_d_target_
Eigen::Quaterniond orientation_d_
Eigen::Matrix< double, 7, 1 > saturateTorqueRate(const Eigen::Matrix< double, 7, 1 > &tau_d_calculated, const Eigen::Matrix< double, 7, 1 > &tau_J_d)
double nullspace_stiffness_
const double delta_tau_max_
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_
Eigen::Matrix< double, 6, 6 > cartesian_damping_
Eigen::Vector3d position_d_
void complianceParamCallback(franka_example_controllers::compliance_paramConfig &config, uint32_t level)
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_target_
std::unique_ptr< franka_hw::FrankaModelHandle > model_handle_
std::vector< hardware_interface::JointHandle > joint_handles_