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 <mutex>
7 #include <string>
8 #include <vector>
9 
11 #include <dynamic_reconfigure/server.h>
12 #include <geometry_msgs/PoseStamped.h>
15 #include <ros/node_handle.h>
16 #include <ros/time.h>
17 #include <Eigen/Dense>
18 
19 #include <franka_example_controllers/compliance_paramConfig.h>
22 
24 
26  franka_hw::FrankaModelInterface,
27  hardware_interface::EffortJointInterface,
28  franka_hw::FrankaStateInterface> {
29  public:
30  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& node_handle) override;
31  void starting(const ros::Time&) override;
32  void update(const ros::Time&, const ros::Duration& period) override;
33 
34  private:
35  // Saturation
36  Eigen::Matrix<double, 7, 1> saturateTorqueRate(
37  const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
38  const Eigen::Matrix<double, 7, 1>& tau_J_d); // NOLINT (readability-identifier-naming)
39 
40  std::unique_ptr<franka_hw::FrankaStateHandle> state_handle_;
41  std::unique_ptr<franka_hw::FrankaModelHandle> model_handle_;
42  std::vector<hardware_interface::JointHandle> joint_handles_;
43 
44  double filter_params_{0.005};
45  double nullspace_stiffness_{20.0};
47  const double delta_tau_max_{1.0};
48  Eigen::Matrix<double, 6, 6> cartesian_stiffness_;
49  Eigen::Matrix<double, 6, 6> cartesian_stiffness_target_;
50  Eigen::Matrix<double, 6, 6> cartesian_damping_;
51  Eigen::Matrix<double, 6, 6> cartesian_damping_target_;
52  Eigen::Matrix<double, 7, 1> q_d_nullspace_;
53  Eigen::Vector3d position_d_;
54  Eigen::Quaterniond orientation_d_;
56  Eigen::Vector3d position_d_target_;
57  Eigen::Quaterniond orientation_d_target_;
58 
59  // Dynamic reconfigure
60  std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>>
63  void complianceParamCallback(franka_example_controllers::compliance_paramConfig& config,
64  uint32_t level);
65 
66  // Equilibrium pose subscriber
68  void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr& msg);
69 };
70 
71 } // namespace franka_example_controllers
franka_example_controllers::CartesianImpedanceExampleController
Definition: cartesian_impedance_example_controller.h:25
franka_example_controllers::CartesianImpedanceExampleController::cartesian_stiffness_
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_
Definition: cartesian_impedance_example_controller.h:48
node_handle.h
franka_example_controllers::CartesianImpedanceExampleController::dynamic_reconfigure_compliance_param_node_
ros::NodeHandle dynamic_reconfigure_compliance_param_node_
Definition: cartesian_impedance_example_controller.h:62
franka_example_controllers::CartesianImpedanceExampleController::starting
void starting(const ros::Time &) override
Definition: cartesian_impedance_example_controller.cpp:108
time.h
franka_example_controllers::CartesianImpedanceExampleController::nullspace_stiffness_target_
double nullspace_stiffness_target_
Definition: cartesian_impedance_example_controller.h:46
franka_example_controllers::CartesianImpedanceExampleController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Definition: cartesian_impedance_example_controller.cpp:17
franka_example_controllers::CartesianImpedanceExampleController::cartesian_stiffness_target_
Eigen::Matrix< double, 6, 6 > cartesian_stiffness_target_
Definition: cartesian_impedance_example_controller.h:49
franka_example_controllers::CartesianImpedanceExampleController::complianceParamCallback
void complianceParamCallback(franka_example_controllers::compliance_paramConfig &config, uint32_t level)
Definition: cartesian_impedance_example_controller.cpp:214
franka_example_controllers
Definition: cartesian_impedance_example_controller.h:23
franka_example_controllers::CartesianImpedanceExampleController::orientation_d_target_
Eigen::Quaterniond orientation_d_target_
Definition: cartesian_impedance_example_controller.h:57
franka_example_controllers::CartesianImpedanceExampleController::dynamic_server_compliance_param_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::compliance_paramConfig > > dynamic_server_compliance_param_
Definition: cartesian_impedance_example_controller.h:61
joint_command_interface.h
franka_example_controllers::CartesianImpedanceExampleController::nullspace_stiffness_
double nullspace_stiffness_
Definition: cartesian_impedance_example_controller.h:45
hardware_interface::RobotHW
franka_example_controllers::CartesianImpedanceExampleController::joint_handles_
std::vector< hardware_interface::JointHandle > joint_handles_
Definition: cartesian_impedance_example_controller.h:42
franka_example_controllers::CartesianImpedanceExampleController::model_handle_
std::unique_ptr< franka_hw::FrankaModelHandle > model_handle_
Definition: cartesian_impedance_example_controller.h:41
controller_interface::MultiInterfaceController
franka_example_controllers::CartesianImpedanceExampleController::equilibriumPoseCallback
void equilibriumPoseCallback(const geometry_msgs::PoseStampedConstPtr &msg)
Definition: cartesian_impedance_example_controller.cpp:231
franka_example_controllers::CartesianImpedanceExampleController::cartesian_damping_target_
Eigen::Matrix< double, 6, 6 > cartesian_damping_target_
Definition: cartesian_impedance_example_controller.h:51
franka_example_controllers::CartesianImpedanceExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition: cartesian_impedance_example_controller.cpp:129
franka_example_controllers::CartesianImpedanceExampleController::sub_equilibrium_pose_
ros::Subscriber sub_equilibrium_pose_
Definition: cartesian_impedance_example_controller.h:67
franka_example_controllers::CartesianImpedanceExampleController::state_handle_
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle_
Definition: cartesian_impedance_example_controller.h:40
franka_state_interface.h
ros::Time
franka_model_interface.h
franka_example_controllers::CartesianImpedanceExampleController::position_and_orientation_d_target_mutex_
std::mutex position_and_orientation_d_target_mutex_
Definition: cartesian_impedance_example_controller.h:55
franka_example_controllers::CartesianImpedanceExampleController::saturateTorqueRate
Eigen::Matrix< double, 7, 1 > saturateTorqueRate(const Eigen::Matrix< double, 7, 1 > &tau_d_calculated, const Eigen::Matrix< double, 7, 1 > &tau_J_d)
Definition: cartesian_impedance_example_controller.cpp:202
robot_hw.h
franka_example_controllers::CartesianImpedanceExampleController::orientation_d_
Eigen::Quaterniond orientation_d_
Definition: cartesian_impedance_example_controller.h:54
franka_example_controllers::CartesianImpedanceExampleController::q_d_nullspace_
Eigen::Matrix< double, 7, 1 > q_d_nullspace_
Definition: cartesian_impedance_example_controller.h:52
franka_example_controllers::CartesianImpedanceExampleController::position_d_
Eigen::Vector3d position_d_
Definition: cartesian_impedance_example_controller.h:53
ros::Duration
franka_example_controllers::CartesianImpedanceExampleController::cartesian_damping_
Eigen::Matrix< double, 6, 6 > cartesian_damping_
Definition: cartesian_impedance_example_controller.h:50
ros::NodeHandle
ros::Subscriber
franka_example_controllers::CartesianImpedanceExampleController::filter_params_
double filter_params_
Definition: cartesian_impedance_example_controller.h:44
franka_example_controllers::CartesianImpedanceExampleController::position_d_target_
Eigen::Vector3d position_d_target_
Definition: cartesian_impedance_example_controller.h:56
franka_example_controllers::CartesianImpedanceExampleController::delta_tau_max_
const double delta_tau_max_
Definition: cartesian_impedance_example_controller.h:47
multi_interface_controller.h


franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:26