9
9
#include < vector>
10
10
11
11
#include " controller_interface/controller_interface.hpp"
12
- #include " hardware_interface/loaned_command_interface.hpp"
12
+ #include " eigen3/Eigen/Core"
13
+ #include " hardware_interface/loaned_state_interface.hpp"
13
14
#include " hardware_interface/types/hardware_interface_type_values.hpp"
14
15
#include " rclcpp/rclcpp.hpp"
16
+ #include " semantic_components/force_torque_sensor.hpp"
15
17
16
18
#include " friLBRState.h"
19
+ #include " lbr_fri_ros2/control.hpp"
17
20
#include " lbr_fri_ros2/types.hpp"
18
21
#include " lbr_ros2_control/system_interface_type_values.hpp"
19
22
20
23
namespace lbr_ros2_control {
21
- class Admittance {
22
- // implement an addmittance...
24
+ struct AdmittanceParameters {
25
+ double m = 1.0 ;
26
+ double b = 0.1 ;
27
+ double k = 0.0 ;
23
28
};
24
29
25
- class AdmittanceController : public controller_interface ::ControllerInterface {
26
- static constexpr uint8_t CARTESIAN_DOF = 6 ;
30
+ class AdmittanceImpl {
31
+ public:
32
+ AdmittanceImpl (const AdmittanceParameters ¶meters) : parameters_(parameters) {}
33
+
34
+ void compute (const Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > &f_ext,
35
+ const Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > &x,
36
+ const Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > &dx,
37
+ Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > &ddx) {
38
+ ddx = (f_ext - parameters_.b * dx - parameters_.k * x) / parameters_.m ;
39
+ }
27
40
41
+ protected:
42
+ AdmittanceParameters parameters_;
43
+ };
44
+
45
+ class AdmittanceController : public controller_interface ::ControllerInterface {
28
46
public:
29
47
AdmittanceController ();
30
48
@@ -47,18 +65,33 @@ class AdmittanceController : public controller_interface::ControllerInterface {
47
65
on_deactivate (const rclcpp_lifecycle::State &previous_state) override ;
48
66
49
67
protected:
50
- bool reference_command_interfaces_ ();
51
68
bool reference_state_interfaces_ ();
52
- void clear_command_interfaces_ ();
53
69
void clear_state_interfaces_ ();
54
70
void configure_joint_names_ ();
55
-
71
+ void configure_admittance_impl_ ();
72
+ void configure_inv_jac_ctrl_impl_ ();
73
+ void zero_all_values_ ();
74
+
75
+ // admittance
76
+ bool initialized_ = false ;
77
+ std::unique_ptr<AdmittanceImpl> admittance_impl_ptr_;
78
+ Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > x_init_, x_prev_;
79
+ Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > f_ext_, x_, dx_, ddx_;
80
+
81
+ // joint veloctiy computation
82
+ std::unique_ptr<lbr_fri_ros2::InvJacCtrlImpl> inv_jac_ctrl_impl_ptr_;
83
+ lbr_fri_ros2::jnt_array_t q_, dq_;
84
+ Eigen::Matrix<double , lbr_fri_ros2::CARTESIAN_DOF, 1 > twist_command_;
85
+
86
+ // interfaces
56
87
lbr_fri_ros2::jnt_name_array_t joint_names_;
57
-
58
- std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
59
- joint_position_command_interfaces_;
60
88
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
61
- estimated_ft_sensor_state_interface_;
89
+ joint_position_state_interfaces_;
90
+ std::unique_ptr<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
91
+ sample_time_state_interface_ptr_;
92
+ std::unique_ptr<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
93
+ session_state_interface_ptr_;
94
+ std::unique_ptr<semantic_components::ForceTorqueSensor> estimated_ft_sensor_ptr_;
62
95
};
63
96
} // namespace lbr_ros2_control
64
97
#endif // LBR_ROS2_CONTROL__ADMITTANCE_CONTROLLER_HPP_
0 commit comments