force_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>
15 #include <ros/node_handle.h>
16 #include <ros/time.h>
17 #include <Eigen/Core>
18 
19 #include <franka_example_controllers/desired_mass_paramConfig.h>
20 
22 
24  franka_hw::FrankaModelInterface,
25  hardware_interface::EffortJointInterface,
26  franka_hw::FrankaStateInterface> {
27  public:
28  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& node_handle) override;
29  void starting(const ros::Time&) override;
30  void update(const ros::Time&, const ros::Duration& period) override;
31 
32  private:
33  // Saturation
34  Eigen::Matrix<double, 7, 1> saturateTorqueRate(
35  const Eigen::Matrix<double, 7, 1>& tau_d_calculated,
36  const Eigen::Matrix<double, 7, 1>& tau_J_d); // NOLINT (readability-identifier-naming)
37 
38  std::unique_ptr<franka_hw::FrankaModelHandle> model_handle_;
39  std::unique_ptr<franka_hw::FrankaStateHandle> state_handle_;
40  std::vector<hardware_interface::JointHandle> joint_handles_;
41 
42  double desired_mass_{0.0};
43  double target_mass_{0.0};
44  double k_p_{0.0};
45  double k_i_{0.0};
46  double target_k_p_{0.0};
47  double target_k_i_{0.0};
48  double filter_gain_{0.001};
49  Eigen::Matrix<double, 7, 1> tau_ext_initial_;
50  Eigen::Matrix<double, 7, 1> tau_error_;
51  static constexpr double kDeltaTauMax{1.0};
52 
53  // Dynamic reconfigure
54  std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::desired_mass_paramConfig>>
57  void desiredMassParamCallback(franka_example_controllers::desired_mass_paramConfig& config,
58  uint32_t level);
59 };
60 
61 } // namespace franka_example_controllers
franka_example_controllers::ForceExampleController
Definition: force_example_controller.h:23
node_handle.h
franka_example_controllers::ForceExampleController::k_p_
double k_p_
Definition: force_example_controller.h:44
franka_example_controllers::ForceExampleController::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: force_example_controller.cpp:138
franka_example_controllers::ForceExampleController::kDeltaTauMax
static constexpr double kDeltaTauMax
Definition: force_example_controller.h:51
franka_example_controllers::ForceExampleController::state_handle_
std::unique_ptr< franka_hw::FrankaStateHandle > state_handle_
Definition: force_example_controller.h:39
franka_example_controllers::ForceExampleController::target_k_p_
double target_k_p_
Definition: force_example_controller.h:46
time.h
franka_example_controllers::ForceExampleController::desiredMassParamCallback
void desiredMassParamCallback(franka_example_controllers::desired_mass_paramConfig &config, uint32_t level)
Definition: force_example_controller.cpp:130
franka_example_controllers::ForceExampleController::tau_error_
Eigen::Matrix< double, 7, 1 > tau_error_
Definition: force_example_controller.h:50
franka_example_controllers::ForceExampleController::joint_handles_
std::vector< hardware_interface::JointHandle > joint_handles_
Definition: force_example_controller.h:40
franka_example_controllers::ForceExampleController::dynamic_reconfigure_desired_mass_param_node_
ros::NodeHandle dynamic_reconfigure_desired_mass_param_node_
Definition: force_example_controller.h:56
franka_example_controllers::ForceExampleController::k_i_
double k_i_
Definition: force_example_controller.h:45
franka_example_controllers::ForceExampleController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override
Definition: force_example_controller.cpp:16
franka_example_controllers::ForceExampleController::filter_gain_
double filter_gain_
Definition: force_example_controller.h:48
franka_example_controllers
Definition: cartesian_impedance_example_controller.h:23
franka_example_controllers::ForceExampleController::dynamic_server_desired_mass_param_
std::unique_ptr< dynamic_reconfigure::Server< franka_example_controllers::desired_mass_paramConfig > > dynamic_server_desired_mass_param_
Definition: force_example_controller.h:55
joint_command_interface.h
hardware_interface::RobotHW
franka_example_controllers::ForceExampleController::starting
void starting(const ros::Time &) override
Definition: force_example_controller.cpp:88
franka_example_controllers::ForceExampleController::target_mass_
double target_mass_
Definition: force_example_controller.h:43
controller_interface::MultiInterfaceController
franka_example_controllers::ForceExampleController::model_handle_
std::unique_ptr< franka_hw::FrankaModelHandle > model_handle_
Definition: force_example_controller.h:38
franka_example_controllers::ForceExampleController::desired_mass_
double desired_mass_
Definition: force_example_controller.h:42
franka_state_interface.h
ros::Time
franka_model_interface.h
franka_example_controllers::ForceExampleController::target_k_i_
double target_k_i_
Definition: force_example_controller.h:47
robot_hw.h
ros::Duration
franka_example_controllers::ForceExampleController::tau_ext_initial_
Eigen::Matrix< double, 7, 1 > tau_ext_initial_
Definition: force_example_controller.h:49
franka_example_controllers::ForceExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition: force_example_controller.cpp:98
ros::NodeHandle
multi_interface_controller.h


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