Skip to content

Commit ac87f66

Browse files
authored
Add gravity compensation filter (#153)
--------- Co-authored-by: Daniel Zumkeller <[email protected]> Co-authored-by: Denis Štogl <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 3ed348a commit ac87f66

11 files changed

+643
-3
lines changed

Diff for: control_toolbox/CMakeLists.txt

+35-3
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ endif()
2020
set(THIS_PACKAGE_INCLUDE_DEPENDS
2121
control_msgs
2222
rclcpp
23+
rcl_interfaces
2324
rcutils
2425
realtime_tools
2526
)
@@ -51,16 +52,36 @@ target_compile_definitions(control_toolbox PRIVATE "CONTROL_TOOLBOX_BUILDING_LIB
5152
########################
5253
set(CONTROL_FILTERS_INCLUDE_DEPENDS
5354
filters
54-
rclcpp
55+
geometry_msgs
5556
generate_parameter_library
5657
pluginlib
57-
geometry_msgs
58+
rclcpp
59+
tf2_geometry_msgs
60+
tf2
61+
tf2_ros
5862
)
63+
5964
foreach(Dependency IN ITEMS ${CONTROL_FILTERS_INCLUDE_DEPENDS})
6065
find_package(${Dependency} REQUIRED)
6166
endforeach()
6267
find_package(Eigen3 REQUIRED NO_MODULE)
6368

69+
generate_parameter_library(
70+
gravity_compensation_filter_parameters
71+
src/control_filters/gravity_compensation_filter_parameters.yaml
72+
)
73+
74+
add_library(gravity_compensation SHARED
75+
src/control_filters/gravity_compensation.cpp
76+
)
77+
target_compile_features(gravity_compensation PUBLIC cxx_std_17)
78+
target_include_directories(gravity_compensation PUBLIC
79+
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
80+
$<INSTALL_INTERFACE:include/control_toolbox>
81+
)
82+
target_link_libraries(gravity_compensation PUBLIC gravity_compensation_filter_parameters)
83+
ament_target_dependencies(gravity_compensation PUBLIC ${CONTROL_FILTERS_INCLUDE_DEPENDS})
84+
6485
generate_parameter_library(
6586
low_pass_filter_parameters
6687
src/control_filters/low_pass_filter_parameters.yaml
@@ -144,6 +165,17 @@ if(BUILD_TESTING)
144165
ament_target_dependencies(pid_ros_publisher_tests rclcpp_lifecycle)
145166

146167
## Control Filters
168+
### Gravity Compensation
169+
add_rostest_with_parameters_gmock(test_gravity_compensation test/control_filters/test_gravity_compensation.cpp
170+
${CMAKE_CURRENT_SOURCE_DIR}/test/control_filters/test_gravity_compensation_parameters.yaml
171+
)
172+
target_link_libraries(test_gravity_compensation gravity_compensation gravity_compensation_filter_parameters)
173+
ament_target_dependencies(test_gravity_compensation ${CONTROL_FILTERS_INCLUDE_DEPENDS})
174+
175+
ament_add_gmock(test_load_gravity_compensation test/control_filters/test_load_gravity_compensation.cpp)
176+
target_link_libraries(test_load_gravity_compensation gravity_compensation gravity_compensation_filter_parameters)
177+
ament_target_dependencies(test_load_gravity_compensation ${CONTROL_FILTERS_INCLUDE_DEPENDS})
178+
147179
# exponential_filter
148180
add_rostest_with_parameters_gmock(test_exponential_filter test/control_filters/test_exponential_filter.cpp
149181
${CMAKE_CURRENT_SOURCE_DIR}/test/control_filters/test_exponential_filter_parameters.yaml
@@ -189,7 +221,7 @@ install(
189221
install(TARGETS control_toolbox
190222
low_pass_filter low_pass_filter_parameters
191223
rate_limiter rate_limiter_parameters
192-
exponential_filter exponential_filter_parameters
224+
exponential_filter exponential_filter_parameters gravity_compensation gravity_compensation_filter_parameters
193225
EXPORT export_control_toolbox
194226
ARCHIVE DESTINATION lib
195227
LIBRARY DESTINATION lib

Diff for: control_toolbox/control_filters.xml

+11
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,15 @@
11
<class_libraries>
2+
<library path="gravity_compensation">
3+
<class name="control_filters/GravityCompensationWrench"
4+
type="control_filters::GravityCompensation&lt;geometry_msgs::msg::WrenchStamped&gt;"
5+
base_class_type="filters::FilterBase&lt;geometry_msgs::msg::WrenchStamped&gt;">
6+
<description>
7+
This is a gravity compensation filter working with geometry_msgs::WrenchStamped.
8+
It subtracts the influence of a force caused by the gravitational force from force
9+
measurements.
10+
</description>
11+
</class>
12+
</library>
213
<library path="low_pass_filter">
314
<class name="control_filters/LowPassFilterDouble"
415
type="control_filters::LowPassFilter&lt;double&gt;"
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,127 @@
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_
16+
#define CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_
17+
18+
#include <exception>
19+
#include <memory>
20+
#include <string>
21+
#include <vector>
22+
23+
#include "filters/filter_base.hpp"
24+
#include "geometry_msgs/msg/vector3_stamped.hpp"
25+
#include "tf2_ros/buffer.h"
26+
#include "tf2_ros/transform_listener.h"
27+
28+
#include "control_toolbox/gravity_compensation_filter_parameters.hpp"
29+
30+
namespace control_filters
31+
{
32+
33+
34+
template <typename T>
35+
class GravityCompensation : public filters::FilterBase<T>
36+
{
37+
public:
38+
/** \brief Constructor */
39+
GravityCompensation();
40+
41+
/** \brief Destructor */
42+
~GravityCompensation();
43+
44+
/** @brief Configure filter parameters */
45+
bool configure() override;
46+
47+
/** \brief Update the filter and return the data separately
48+
* \param data_in T array with length width
49+
* \param data_out T array with length width
50+
*/
51+
bool update(const T & data_in, T & data_out) override;
52+
53+
protected:
54+
void compute_internal_params()
55+
{
56+
cog_.vector.x = parameters_.tool.CoG[0];
57+
cog_.vector.y = parameters_.tool.CoG[1];
58+
cog_.vector.z = parameters_.tool.CoG[2];
59+
cst_ext_force_.vector.x = parameters_.tool.gravity_field[0]*parameters_.tool.mass;
60+
cst_ext_force_.vector.y = parameters_.tool.gravity_field[1]*parameters_.tool.mass;
61+
cst_ext_force_.vector.z = parameters_.tool.gravity_field[2]*parameters_.tool.mass;
62+
};
63+
64+
private:
65+
rclcpp::Clock::SharedPtr clock_;
66+
std::shared_ptr<rclcpp::Logger> logger_;
67+
std::shared_ptr<gravity_compensation_filter::ParamListener> parameter_handler_;
68+
gravity_compensation_filter::Params parameters_;
69+
70+
// Frames for Transformation of Gravity / CoG Vector
71+
std::string world_frame_; // frame in which gravity is given
72+
std::string sensor_frame_; // frame in which Cog is given and compution occur
73+
// Storage for Calibration Values
74+
geometry_msgs::msg::Vector3Stamped cog_; // Center of Gravity Vector (wrt sensor frame)
75+
geometry_msgs::msg::Vector3Stamped cst_ext_force_; // Gravity Force Vector (wrt world frame)
76+
77+
// Filter objects
78+
std::unique_ptr<tf2_ros::Buffer> p_tf_Buffer_;
79+
std::unique_ptr<tf2_ros::TransformListener> p_tf_Listener_;
80+
geometry_msgs::msg::TransformStamped transform_sensor_datain_, transform_world_dataout_,
81+
transform_data_out_sensor_, transform_sensor_world_;
82+
};
83+
84+
template <typename T>
85+
GravityCompensation<T>::GravityCompensation()
86+
{
87+
}
88+
89+
template <typename T>
90+
GravityCompensation<T>::~GravityCompensation()
91+
{
92+
}
93+
94+
template <typename T>
95+
bool GravityCompensation<T>::configure()
96+
{
97+
clock_ = std::make_shared<rclcpp::Clock>(RCL_ROS_TIME);
98+
p_tf_Buffer_.reset(new tf2_ros::Buffer(clock_));
99+
p_tf_Listener_.reset(new tf2_ros::TransformListener(*p_tf_Buffer_.get(), true));
100+
101+
logger_.reset(
102+
new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
103+
104+
// Initialize the parameter_listener once
105+
if (!parameter_handler_)
106+
{
107+
try
108+
{
109+
parameter_handler_ =
110+
std::make_shared<gravity_compensation_filter::ParamListener>(this->params_interface_,
111+
this->param_prefix_);
112+
}
113+
catch (std::exception & ex) {
114+
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what());
115+
parameter_handler_.reset();
116+
throw;
117+
}
118+
}
119+
parameters_ = parameter_handler_->get_params();
120+
compute_internal_params();
121+
122+
return true;
123+
}
124+
125+
} // namespace control_filters
126+
127+
#endif // CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_

Diff for: control_toolbox/package.xml

+3
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,9 @@
3232
<depend>rclcpp</depend>
3333
<depend>rcutils</depend>
3434
<depend>realtime_tools</depend>
35+
<depend>tf2</depend>
36+
<depend>tf2_ros</depend>
37+
<depend>tf2_geometry_msgs</depend>
3538

3639
<test_depend>ament_cmake_gmock</test_depend>
3740
<test_depend>rclcpp_lifecycle</test_depend>

Diff for: control_toolbox/src/control_filters/README.md

+57
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,65 @@ Implement filter plugins for control purposes as https://index.ros.org/r/filters
44

55
## Available filters
66

7+
* Gravity Compensation: implements a gravity compensation algorithm, removing the gravity component from the incoming data (Wrench).
78
* Low Pass: implements a low-pass filter based on a time-invariant [Infinite Impulse Response (IIR) filter](https://en.wikipedia.org/wiki/Infinite_impulse_response), for different data types (doubles or wrench).
89
* Exponential Filter: Exponential filter for double data type.
910

11+
12+
## Gravity compensation filter
13+
14+
This filter implements an algorithm compensating for the gravity forces acting at the center of gravity (CoG) of a known mass, computed at a `sensor_frame` and applied to a `data_in` wrench.
15+
16+
The filter relies on tf2, and might fail if transforms are missing.
17+
18+
Note that, for convenience, the filter can perform additional frame changes if data_out frame id is given.
19+
20+
### Required parameters
21+
22+
* `world_frame` (&Rscr;<sub>w</sub>): frame in which the `CoG.force` is represented.
23+
* `sensor_frame` (&Rscr;<sub>s</sub>): frame in which the `CoG.pos` is defined
24+
* `CoG.pos` (p<sub>s</sub>): position of the CoG of the mass the filter should compensate for
25+
* `CoG.force` (g<sub>w</sub>): constant (but updatable) force of gravity at the Cog (typically m.G), defined along axes of the `world_frame`
26+
27+
### Algorithm
28+
29+
Given
30+
31+
* above-required parameters, &Rscr;<sub>w</sub>, &Rscr;<sub>s</sub>, p<sub>s</sub>, g<sub>w</sub>
32+
* `data_in`, a wrench &Fscr;<sub>i</sub> = {f<sub>i</sub>, &tau;<sub>i</sub>} represented in the `data_in` frame &Rscr;<sub>i</sub>
33+
* access to tf2 homogeneous transforms:
34+
* T<sub>si</sub> from &Rscr;<sub>i</sub> to &Rscr;<sub>s</sub>
35+
* T<sub>sw</sub> from &Rscr;<sub>w</sub> to &Rscr;<sub>s</sub>
36+
* T<sub>os</sub> from &Rscr;<sub>s</sub> to &Rscr;<sub>o</sub>
37+
38+
Compute `data_out` compensated wrench &Fscr;c<sub>o</sub> = {fc<sub>o</sub>, &tau;c<sub>o</sub>} represented in the `data_out` frame &Rscr;<sub>o</sub> if given, or the `data_in` frame &Rscr;<sub>i</sub> otherwise, with equations:
39+
40+
&Fscr;c<sub>o</sub> = T<sub>os</sub>.&Fscr;c<sub>s</sub>,
41+
42+
43+
with &Fscr;c<sub>s</sub> = {fc<sub>s</sub>, &tau;c<sub>s</sub>} the compensated wrench in `sensor_frame` (common frame for computation)
44+
45+
and,
46+
47+
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>g<sub>w</sub>
48+
49+
its force and,
50+
51+
&tau;c<sub>s</sub> = &tau;<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>g<sub>w</sub>)
52+
53+
its torque, and
54+
55+
&Fscr;<sub>s</sub> = T<sub>si</sub>.&Fscr;<sub>i</sub> = {f<sub>s</sub>, &tau;<sub>s</sub>}
56+
57+
the full transform of the input wrench &Fscr;<sub>i</sub> to sensor frame &Rscr;<sub>s</sub>
58+
59+
Remarks :
60+
* a full vector is used for gravity force, to not impose gravity to be only along z of `world_frame`.
61+
* `data_in` frame is usually equal to `sensor_frame`, but could be different since measurement of wrench might occur in another frame. E.g.: measurements are at the **FT sensor flange** = `data_in` frame, but CoG is given in **FT sensor base** = `sensor_frame` (=frame to which it is mounted on the robot), introducing an offset (thickness of the sensor) to be accounted for.
62+
* `data_out` frame is usually `data_in` frame, but for convenience, can be set to any other useful frame. E.g.: wrench expressed in a `control_frame` like the center of a gripper.
63+
* T<sub>sw</sub> will only rotate the g<sub>w</sub> vector, because gravity is a field applied everywhere, and not a wrench (no torque should be induced by transforming from &Rscr;<sub>w</sub> to &Rscr;<sub>s</sub>).
64+
65+
1066
## Low Pass filter
1167

1268
This filter implements a low-pass filter in the form of an [IIR filter](https://en.wikipedia.org/wiki/Infinite_impulse_response), applied to a `data_in` (double or wrench).
@@ -21,6 +77,7 @@ The feedforward and feedback coefficients of the IIR filter are computed from th
2177
### Algorithm
2278

2379
Given
80+
2481
* above-required parameters, `sf`, `df`, `di`
2582
* `data_in`, a double or wrench `x`
2683

0 commit comments

Comments
 (0)