cartesian_impedance_example_controller.h
Go to the documentation of this file.
1 // Copyright (c) 2017 Franka Emika GmbH
2 // Use of this source code is governed by the Apache-2.0 license, see LICENSE
3 #pragma once
4 
5 #include <memory>
6 #include <string>
7 #include <vector>
8 
10 #include <dynamic_reconfigure/server.h>
11 #include <geometry_msgs/PoseStamped.h>
14 #include <ros/node_handle.h>
15 #include <ros/time.h>
16 #include <Eigen/Dense>
17 
18 #include <franka_example_controllers/compliance_paramConfig.h>
21 
23 
25  franka_hw::FrankaModelInterface,
26  hardware_interface::EffortJointInterface,
27  franka_hw::FrankaStateInterface> {
28  public:
29  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& node_handle) override;
30  void starting(const ros::Time&) override;
31  void update(const ros::Time&, const ros::Duration& period) override;
32 
33  private:
34  // Saturation
35  Eigen::Matrix<double, 7, 1> saturateTorqueRate(
36  const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
37  const Eigen::Matrix<double, 7, 1>& tau_J_d); // NOLINT (readability-identifier-naming)
38 
39  std::unique_ptr<franka_hw::FrankaStateHandle> state_handle_;
40  std::unique_ptr<franka_hw::FrankaModelHandle> model_handle_;
41  std::vector<hardware_interface::JointHandle> joint_handles_;
42 
43  double filter_params_{0.005};
44  double nullspace_stiffness_{20.0};
46  const double delta_tau_max_{1.0};
47  Eigen::Matrix<double, 6, 6> cartesian_stiffness_;
48  Eigen::Matrix<double, 6, 6> cartesian_stiffness_target_;
49  Eigen::Matrix<double, 6, 6> cartesian_damping_;
50  Eigen::Matrix<double, 6, 6> cartesian_damping_target_;
51  Eigen::Matrix<double, 7, 1> q_d_nullspace_;
52  Eigen::Vector3d position_d_;
53  Eigen::Quaterniond orientation_d_;
54  Eigen::Vector3d position_d_target_;
55  Eigen::Quaterniond orientation_d_target_;
56 
57  // Dynamic reconfigure
58  std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>
61  void complianceParamCallback(franka_example_controllers::compliance_paramConfig& config,
62  uint32_t level);
63 
64  // Equilibrium pose subscriber
66  void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr& msg);
67 };
68 
69 } // namespace franka_example_controllers
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
void update(const ros::Time &, const ros::Duration &period) override
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Eigen::Matrix< double, 7, 1 > saturateTorqueRate(const Eigen::Matrix< double, 7, 1 > &tau_d_calculated, const Eigen::Matrix< double, 7, 1 > &tau_J_d)
void complianceParamCallback(franka_example_controllers::compliance_paramConfig &config, uint32_t level)


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Fri Oct 23 2020 03:47:17