Skip to content

Commit 836f30c

Browse files
committed
initial admittance controller impl (#163)
1 parent 5fdaed9 commit 836f30c

File tree

10 files changed

+399
-146
lines changed

10 files changed

+399
-146
lines changed

lbr_fri_ros2/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ find_package(control_toolbox REQUIRED)
1515
find_package(eigen3_cmake_module REQUIRED)
1616
find_package(Eigen3)
1717
find_package(FRIClient REQUIRED)
18+
find_package(geometry_msgs REQUIRED)
1819
find_package(kdl_parser REQUIRED)
1920
find_package(lbr_fri_idl REQUIRED)
2021
find_package(orocos_kdl_vendor REQUIRED)
@@ -33,6 +34,7 @@ add_library(lbr_fri_ros2
3334
src/app.cpp
3435
src/async_client.cpp
3536
src/command_guard.cpp
37+
src/control.cpp
3638
src/filters.cpp
3739
src/ft_estimator.cpp
3840
src/kinematics.cpp
@@ -48,6 +50,7 @@ target_include_directories(lbr_fri_ros2
4850
ament_target_dependencies(lbr_fri_ros2
4951
control_toolbox
5052
Eigen3
53+
geometry_msgs
5154
kdl_parser
5255
lbr_fri_idl
5356
orocos_kdl_vendor
@@ -65,6 +68,7 @@ ament_export_dependencies(
6568
eigen3_cmake_module
6669
Eigen3
6770
FRIClient
71+
geometry_msgs
6872
kdl_parser
6973
lbr_fri_idl
7074
orocos_kdl_vendor
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
#ifndef LBR_FRI_ROS2__CONTROL_HPP_
2+
#define LBR_FRI_ROS2__CONTROL_HPP_
3+
4+
#include <algorithm>
5+
#include <memory>
6+
#include <string>
7+
8+
#include "eigen3/Eigen/Core"
9+
#include "geometry_msgs/msg/twist.hpp"
10+
11+
#include "lbr_fri_ros2/kinematics.hpp"
12+
#include "lbr_fri_ros2/pinv.hpp"
13+
#include "lbr_fri_ros2/types.hpp"
14+
15+
namespace lbr_fri_ros2 {
16+
struct InvJacCtrlParameters {
17+
std::string chain_root;
18+
std::string chain_tip;
19+
bool twist_in_tip_frame;
20+
double damping;
21+
double max_linear_velocity;
22+
double max_angular_velocity;
23+
};
24+
25+
class InvJacCtrlImpl {
26+
public:
27+
InvJacCtrlImpl(const std::string &robot_description, const InvJacCtrlParameters &parameters);
28+
29+
void compute(const geometry_msgs::msg::Twist::SharedPtr &twist_target, const_jnt_array_t_ref q,
30+
jnt_array_t_ref dq);
31+
void compute(const_cart_array_t_ref twist_target, const_jnt_array_t_ref q, jnt_array_t_ref dq);
32+
void compute(const Eigen::Matrix<double, CARTESIAN_DOF, 1> &twist_target, const_jnt_array_t_ref q,
33+
jnt_array_t_ref dq);
34+
35+
inline const std::unique_ptr<Kinematics> &get_kinematics_ptr() const { return kinematics_ptr_; };
36+
37+
protected:
38+
void compute_impl_(const_jnt_array_t_ref q, jnt_array_t_ref dq);
39+
40+
InvJacCtrlParameters parameters_;
41+
42+
jnt_array_t q_;
43+
std::unique_ptr<Kinematics> kinematics_ptr_;
44+
Eigen::Matrix<double, N_JNTS, CARTESIAN_DOF> jacobian_inv_;
45+
Eigen::Matrix<double, CARTESIAN_DOF, 1> twist_target_;
46+
};
47+
} // namespace lbr_fri_ros2
48+
#endif // LBR_FRI_ROS2__CONTROL_HPP_

lbr_fri_ros2/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
<depend>control_toolbox</depend>
1717
<depend>fri_client_sdk</depend>
18+
<depend>geometry_msgs</depend>
1819
<depend>kdl_parser</depend>
1920
<depend>lbr_fri_idl</depend>
2021
<depend>orocos_kdl_vendor</depend>

lbr_fri_ros2/src/control.cpp

+72
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
#include "lbr_fri_ros2/control.hpp"
2+
3+
namespace lbr_fri_ros2 {
4+
InvJacCtrlImpl::InvJacCtrlImpl(const std::string &robot_description,
5+
const InvJacCtrlParameters &parameters)
6+
: parameters_(parameters) {
7+
kinematics_ptr_ = std::make_unique<Kinematics>(robot_description, parameters_.chain_root,
8+
parameters_.chain_tip);
9+
}
10+
11+
void InvJacCtrlImpl::compute(const geometry_msgs::msg::Twist::SharedPtr &twist_target,
12+
const_jnt_array_t_ref q, jnt_array_t_ref dq) {
13+
// twist to Eigen
14+
twist_target_[0] = twist_target->linear.x;
15+
twist_target_[1] = twist_target->linear.y;
16+
twist_target_[2] = twist_target->linear.z;
17+
twist_target_[3] = twist_target->angular.x;
18+
twist_target_[4] = twist_target->angular.y;
19+
twist_target_[5] = twist_target->angular.z;
20+
21+
// compute
22+
compute_impl_(q, dq);
23+
}
24+
25+
void InvJacCtrlImpl::compute(const_cart_array_t_ref twist_target, const_jnt_array_t_ref q,
26+
jnt_array_t_ref dq) {
27+
// twist to Eigen
28+
twist_target_[0] = twist_target[0];
29+
twist_target_[1] = twist_target[1];
30+
twist_target_[2] = twist_target[2];
31+
twist_target_[3] = twist_target[3];
32+
twist_target_[4] = twist_target[4];
33+
twist_target_[5] = twist_target[5];
34+
35+
// compute
36+
compute_impl_(q, dq);
37+
}
38+
39+
void InvJacCtrlImpl::compute(const Eigen::Matrix<double, CARTESIAN_DOF, 1> &twist_target,
40+
const_jnt_array_t_ref q, jnt_array_t_ref dq) {
41+
twist_target_ = twist_target;
42+
43+
// compute
44+
compute_impl_(q, dq);
45+
}
46+
47+
void InvJacCtrlImpl::compute_impl_(const_jnt_array_t_ref q, jnt_array_t_ref dq) {
48+
// clip velocity
49+
twist_target_.head(3).unaryExpr([&](double v) {
50+
return std::clamp(v, -parameters_.max_linear_velocity, parameters_.max_linear_velocity);
51+
});
52+
twist_target_.tail(3).unaryExpr([&](double v) {
53+
return std::clamp(v, -parameters_.max_angular_velocity, parameters_.max_angular_velocity);
54+
});
55+
56+
// if desired, transform to tip frame
57+
if (parameters_.twist_in_tip_frame) {
58+
auto chain_tip_frame = kinematics_ptr_->compute_fk(q);
59+
twist_target_.topRows(3) =
60+
Eigen::Matrix3d::Map(chain_tip_frame.M.data).transpose() * twist_target_.topRows(3);
61+
twist_target_.bottomRows(3) =
62+
Eigen::Matrix3d::Map(chain_tip_frame.M.data).transpose() * twist_target_.bottomRows(3);
63+
}
64+
65+
// compute jacobian
66+
auto jacobian = kinematics_ptr_->compute_jacobian(q);
67+
jacobian_inv_ = pinv(jacobian.data, parameters_.damping);
68+
69+
// compute target joint veloctiy and map it to dq
70+
Eigen::Map<Eigen::Matrix<double, N_JNTS, 1>>(dq.data()) = jacobian_inv_ * twist_target_;
71+
}
72+
} // namespace lbr_fri_ros2

lbr_ros2_control/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ find_package(realtime_tools REQUIRED)
3131
add_library(
3232
${PROJECT_NAME}
3333
SHARED
34+
src/controllers/admittance_controller.cpp
3435
src/controllers/lbr_joint_position_command_controller.cpp
3536
src/controllers/lbr_torque_command_controller.cpp
3637
src/controllers/lbr_wrench_command_controller.cpp

lbr_ros2_control/config/lbr_controllers.yaml

+21-6
Original file line numberDiff line numberDiff line change
@@ -93,13 +93,28 @@
9393
ros__parameters:
9494
robot_name: lbr
9595

96+
/**/admittance_controller:
97+
ros__parameters:
98+
robot_name: lbr
99+
admittance:
100+
mass: 0.2
101+
damping: 0.1
102+
stiffness: 0.0
103+
inv_jac_ctrl:
104+
chain_root: lbr_link_0
105+
chain_tip: lbr_link_ee
106+
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
107+
max_linear_velocity: 0.1 # maximum linear velocity
108+
max_angular_velocity: 0.1 # maximum linear acceleration
109+
96110
/**/twist_controller:
97111
ros__parameters:
98112
robot_name: lbr
99-
chain_root: lbr_link_0
100-
chain_tip: lbr_link_ee
101-
twist_in_tip_frame: true # if true, the twist command is expressed in the tip frame, otherwise in the root frame
102-
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
103-
max_linear_velocity: 0.1 # maximum linear velocity
104-
max_angular_velocity: 0.1 # maximum linear acceleration
113+
inv_jac_ctrl:
114+
chain_root: lbr_link_0
115+
chain_tip: lbr_link_ee
116+
twist_in_tip_frame: true # if true, the twist command is expressed in the tip frame, otherwise in the root frame
117+
damping: 0.2 # damping factor for the pseudo-inverse of the Jacobian
118+
max_linear_velocity: 0.1 # maximum linear velocity
119+
max_angular_velocity: 0.1 # maximum linear acceleration
105120
timeout: 0.2 # stop controller if no command is received within this time [s]

lbr_ros2_control/include/lbr_ros2_control/controllers/admittance_controller.hpp

+45-12
Original file line numberDiff line numberDiff line change
@@ -9,22 +9,40 @@
99
#include <vector>
1010

1111
#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"
1314
#include "hardware_interface/types/hardware_interface_type_values.hpp"
1415
#include "rclcpp/rclcpp.hpp"
16+
#include "semantic_components/force_torque_sensor.hpp"
1517

1618
#include "friLBRState.h"
19+
#include "lbr_fri_ros2/control.hpp"
1720
#include "lbr_fri_ros2/types.hpp"
1821
#include "lbr_ros2_control/system_interface_type_values.hpp"
1922

2023
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;
2328
};
2429

25-
class AdmittanceController : public controller_interface::ControllerInterface {
26-
static constexpr uint8_t CARTESIAN_DOF = 6;
30+
class AdmittanceImpl {
31+
public:
32+
AdmittanceImpl(const AdmittanceParameters &parameters) : 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+
}
2740

41+
protected:
42+
AdmittanceParameters parameters_;
43+
};
44+
45+
class AdmittanceController : public controller_interface::ControllerInterface {
2846
public:
2947
AdmittanceController();
3048

@@ -47,18 +65,33 @@ class AdmittanceController : public controller_interface::ControllerInterface {
4765
on_deactivate(const rclcpp_lifecycle::State &previous_state) override;
4866

4967
protected:
50-
bool reference_command_interfaces_();
5168
bool reference_state_interfaces_();
52-
void clear_command_interfaces_();
5369
void clear_state_interfaces_();
5470
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
5687
lbr_fri_ros2::jnt_name_array_t joint_names_;
57-
58-
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
59-
joint_position_command_interfaces_;
6088
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_;
6295
};
6396
} // namespace lbr_ros2_control
6497
#endif // LBR_ROS2_CONTROL__ADMITTANCE_CONTROLLER_HPP_

lbr_ros2_control/include/lbr_ros2_control/controllers/twist_controller.hpp

+5-32
Original file line numberDiff line numberDiff line change
@@ -4,14 +4,12 @@
44
#include <algorithm>
55
#include <array>
66
#include <atomic>
7-
#include <functional>
87
#include <memory>
98
#include <stdexcept>
109
#include <string>
1110
#include <vector>
1211

1312
#include "controller_interface/controller_interface.hpp"
14-
#include "eigen3/Eigen/Core"
1513
#include "geometry_msgs/msg/twist.hpp"
1614
#include "hardware_interface/loaned_state_interface.hpp"
1715
#include "hardware_interface/types/hardware_interface_type_values.hpp"
@@ -20,37 +18,12 @@
2018

2119
#include "friLBRState.h"
2220

21+
#include "lbr_fri_ros2/control.hpp"
2322
#include "lbr_fri_ros2/kinematics.hpp"
24-
#include "lbr_fri_ros2/pinv.hpp"
2523
#include "lbr_fri_ros2/types.hpp"
2624
#include "lbr_ros2_control/system_interface_type_values.hpp"
2725

2826
namespace lbr_ros2_control {
29-
struct TwistParameters {
30-
std::string chain_root;
31-
std::string chain_tip;
32-
bool twist_in_tip_frame;
33-
double damping;
34-
double max_linear_velocity;
35-
double max_angular_velocity;
36-
};
37-
38-
class TwistImpl {
39-
public:
40-
TwistImpl(const std::string &robot_description, const TwistParameters &parameters);
41-
42-
void compute(const geometry_msgs::msg::Twist::SharedPtr &twist_target,
43-
lbr_fri_ros2::const_jnt_array_t_ref q, lbr_fri_ros2::jnt_array_t_ref dq);
44-
45-
protected:
46-
TwistParameters parameters_;
47-
48-
lbr_fri_ros2::jnt_array_t q_;
49-
std::unique_ptr<lbr_fri_ros2::Kinematics> kinematics_ptr_;
50-
Eigen::Matrix<double, lbr_fri_ros2::N_JNTS, lbr_fri_ros2::CARTESIAN_DOF> jacobian_inv_;
51-
Eigen::Matrix<double, lbr_fri_ros2::CARTESIAN_DOF, 1> twist_target_;
52-
};
53-
5427
class TwistController : public controller_interface::ControllerInterface {
5528
public:
5629
TwistController();
@@ -78,24 +51,24 @@ class TwistController : public controller_interface::ControllerInterface {
7851
void clear_state_interfaces_();
7952
void reset_command_buffer_();
8053
void configure_joint_names_();
81-
void configure_twist_impl_();
54+
void configure_inv_jac_ctrl_impl_();
8255

8356
// some safety checks
8457
std::atomic<int> updates_since_last_command_ = 0;
8558
double timeout_ = 0.2;
8659

8760
// joint veloctiy computation
88-
std::unique_ptr<TwistImpl> twist_impl_ptr_;
61+
std::unique_ptr<lbr_fri_ros2::InvJacCtrlImpl> inv_jac_ctrl_impl_ptr_;
8962
lbr_fri_ros2::jnt_array_t q_, dq_;
9063

9164
// interfaces
9265
lbr_fri_ros2::jnt_name_array_t joint_names_;
9366
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
9467
joint_position_state_interfaces_;
9568
std::unique_ptr<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
96-
sample_time_state_interface_;
69+
sample_time_state_interface_ptr_;
9770
std::unique_ptr<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
98-
session_state_interface_;
71+
session_state_interface_ptr_;
9972

10073
// real-time twist command topic
10174
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist::SharedPtr> rt_twist_ptr_;

0 commit comments

Comments
 (0)