-
Notifications
You must be signed in to change notification settings - Fork 98
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add gravity compensation filter #153
base: ros2-master
Are you sure you want to change the base?
Changes from 22 commits
5471301
7532c93
d61437a
e63a7a1
d5a55a7
3817947
c046598
e6d3e27
9cee59e
5715e8f
fcb9cca
b18ffbd
ebd7481
b7ffc66
94ed150
fc47ee0
c910033
8fec166
73072fb
fdf43db
b74a1ee
88d6b8a
b22a754
f181fe7
819941c
1c960dd
7b59f3c
5915fe1
1e7d9dc
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,13 @@ | ||
<class_libraries> | ||
<library path="gravity_compensation"> | ||
<class name="control_filters/GravityCompensationWrench" | ||
type="control_filters::GravityCompensation<geometry_msgs::msg::WrenchStamped>" | ||
base_class_type="filters::FilterBase<geometry_msgs::msg::WrenchStamped>"> | ||
<description> | ||
This is a gravity compensation filter working with geometry_msgs::WrenchStamped. | ||
It subtracts the influence of a force caused by the gravitational force from force | ||
measurements. | ||
</description> | ||
</class> | ||
</library> | ||
</class_libraries> |
Original file line number | Diff line number | Diff line change | ||
---|---|---|---|---|
@@ -0,0 +1,131 @@ | ||||
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt) | ||||
// | ||||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||||
// you may not use this file except in compliance with the License. | ||||
// You may obtain a copy of the License at | ||||
// | ||||
// http://www.apache.org/licenses/LICENSE-2.0 | ||||
// | ||||
// Unless required by applicable law or agreed to in writing, software | ||||
// distributed under the License is distributed on an "AS IS" BASIS, | ||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||||
// See the License for the specific language governing permissions and | ||||
// limitations under the License. | ||||
|
||||
#ifndef CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_ | ||||
#define CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_ | ||||
|
||||
#include <memory> | ||||
#include <string> | ||||
#include <vector> | ||||
|
||||
#include "gravity_compensation_filter_parameters.hpp" | ||||
#include "filters/filter_base.hpp" | ||||
#include "geometry_msgs/msg/vector3_stamped.hpp" | ||||
#include "tf2_ros/buffer.h" | ||||
#include "tf2_ros/transform_listener.h" | ||||
|
||||
namespace control_filters | ||||
{ | ||||
|
||||
|
||||
|
||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||
template <typename T> | ||||
class GravityCompensation : public filters::FilterBase<T> | ||||
{ | ||||
public: | ||||
/** \brief Constructor */ | ||||
GravityCompensation(); | ||||
|
||||
/** \brief Destructor */ | ||||
~GravityCompensation(); | ||||
|
||||
/** @brief Configure filter parameters */ | ||||
bool configure() override; | ||||
|
||||
/** \brief Update the filter and return the data separately | ||||
* \param data_in T array with length width | ||||
* \param data_out T array with length width | ||||
*/ | ||||
bool update(const T & data_in, T & data_out) override; | ||||
|
||||
protected: | ||||
void compute_internal_params() | ||||
{ | ||||
cog_.vector.x = parameters_.CoG.pos[0]; | ||||
cog_.vector.y = parameters_.CoG.pos[1]; | ||||
cog_.vector.z = parameters_.CoG.pos[2]; | ||||
cst_ext_force_.vector.x = parameters_.CoG.force[0]; | ||||
cst_ext_force_.vector.y = parameters_.CoG.force[1]; | ||||
cst_ext_force_.vector.z = parameters_.CoG.force[2]; | ||||
}; | ||||
|
||||
private: | ||||
rclcpp::Clock::SharedPtr clock_; | ||||
std::shared_ptr<rclcpp::Logger> logger_; | ||||
std::shared_ptr<gravity_compensation_filter::ParamListener> parameter_handler_; | ||||
gravity_compensation_filter::Params parameters_; | ||||
|
||||
// Frames for Transformation of Gravity / CoG Vector | ||||
std::string world_frame_; // frame in which gravity is given | ||||
std::string sensor_frame_; // frame in which Cog is given and compution occur | ||||
// Storage for Calibration Values | ||||
geometry_msgs::msg::Vector3Stamped cog_; // Center of Gravity Vector (wrt sensor frame) | ||||
geometry_msgs::msg::Vector3Stamped cst_ext_force_; // Gravity Force Vector (wrt world frame) | ||||
|
||||
// Filter objects | ||||
std::unique_ptr<tf2_ros::Buffer> p_tf_Buffer_; | ||||
std::unique_ptr<tf2_ros::TransformListener> p_tf_Listener_; | ||||
geometry_msgs::msg::TransformStamped transform_sensor_datain_, transform_world_dataout_, | ||||
transform_data_out_sensor_, transform_sensor_world_; | ||||
}; | ||||
|
||||
template <typename T> | ||||
GravityCompensation<T>::GravityCompensation() | ||||
{ | ||||
} | ||||
|
||||
template <typename T> | ||||
GravityCompensation<T>::~GravityCompensation() | ||||
{ | ||||
} | ||||
|
||||
template <typename T> | ||||
bool GravityCompensation<T>::configure() | ||||
{ | ||||
clock_ = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME); | ||||
p_tf_Buffer_.reset(new tf2_ros::Buffer(clock_)); | ||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. would it be possible to get somehow clock from the node? This could lead to wrong definition of clocks and thus not getting correct transformations. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Unless the filter_base is changed, I don't think the filter has any access to the node (only its logger and parameter interfaces). Maybe the filter should get a time and dt passed when updated (as controllers do) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. maybe for a follow-up PR, you could augment the filterbase to also store a clock interface |
||||
p_tf_Listener_.reset(new tf2_ros::TransformListener(*p_tf_Buffer_.get(), true)); | ||||
|
||||
logger_.reset( | ||||
new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_))); | ||||
|
||||
// Initialize the parameter_listener once | ||||
if (!parameter_handler_) | ||||
{ | ||||
try | ||||
{ | ||||
parameter_handler_ = | ||||
std::make_shared<gravity_compensation_filter::ParamListener>(this->params_interface_, | ||||
this->param_prefix_); | ||||
} | ||||
catch (rclcpp::exceptions::ParameterUninitializedException & ex) { | ||||
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what()); | ||||
parameter_handler_.reset(); | ||||
return false; | ||||
} | ||||
catch (rclcpp::exceptions::InvalidParameterValueException & ex) { | ||||
RCLCPP_ERROR((*logger_), "GravityCompensation filter cannot be configured: %s", ex.what()); | ||||
parameter_handler_.reset(); | ||||
return false; | ||||
} | ||||
} | ||||
parameters_ = parameter_handler_->get_params(); | ||||
compute_internal_params(); | ||||
|
||||
return true; | ||||
} | ||||
|
||||
} // namespace control_filters | ||||
|
||||
#endif // CONTROL_FILTERS__GRAVITY_COMPENSATION_HPP_ |
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
@@ -0,0 +1,59 @@ | ||||||
# Control Filters | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
## Available filters | ||||||
|
||||||
* Gravity Compensation: implements a gravity compensation algorithm, removing the gravity component from the incoming data (Wrench). | ||||||
* | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
|
||||||
## Gravity Compensation filter | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
This filter implements a gravity compensation algorithm, applied to an `data_in wrench`, computed at a `sensor frame` in which the center of gravity (CoG) of the to-be-compensated mass is known. | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
The filter relies on ROS TF, and might fail if transforms are missing. | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
Note that, for convenience, the filter can perform additional frame changes if data_out frame id is given. | ||||||
|
||||||
### required parameters | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
* `world_frame` (ℛ<sub>w</sub>): frame in which the `CoG.force` is represented. | ||||||
* `sensor_frame` (ℛ<sub>s</sub>): frame in which the `CoG.pos` is defined | ||||||
* `CoG.pos` (p<sub>s</sub>): position of the CoG of the mass the filter should compensate for | ||||||
* `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` | ||||||
|
||||||
### algorithm | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
Given | ||||||
* above-required parameters, ℛ<sub>w</sub>, ℛ<sub>s</sub>, p<sub>s</sub>, g<sub>w</sub> | ||||||
* `data_in`, a wrench ℱ<sub>i</sub> = {f<sub>i</sub>, τ<sub>i</sub>} represented in `data_in.frame` ℛ<sub>i</sub> | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
* access to TF homogeneous transforms: | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
* T<sub>si</sub> from ℛ<sub>i</sub> to ℛ<sub>s</sub> | ||||||
* T<sub>sw</sub> from ℛ<sub>w</sub> to ℛ<sub>s</sub> | ||||||
* T<sub>os</sub> from ℛ<sub>s</sub> to ℛ<sub>o</sub> | ||||||
|
||||||
Compute `data_out` compensated wrench ℱc<sub>o</sub> = {fc<sub>o</sub>, τc<sub>o</sub>} represented in `data_out.frame` ℛ<sub>o</sub> if given, or `data_in.frame` ℛ<sub>i</sub> otherwise, with equations: | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
ℱc<sub>o</sub> = T<sub>os</sub>.ℱc<sub>s</sub>, | ||||||
|
||||||
|
||||||
with ℱc<sub>s</sub> = {fc<sub>s</sub>, τc<sub>s</sub>} the compensated wrench in `sensor_frame` (common frame for computation) | ||||||
|
||||||
and, | ||||||
|
||||||
fc<sub>s</sub> = f<sub>s</sub> - T<sub>sw</sub>.g<sub>w</sub> | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
its force and, | ||||||
|
||||||
τc<sub>s</sub> = τ<sub>s</sub> - p<sub>s</sub> x (T<sub>sw</sub>.g<sub>w</sub>) | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
its torque, and | ||||||
|
||||||
ℱ<sub>s</sub> = T<sub>si</sub>.ℱ<sub>i</sub> | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
|
||||||
the full transform of the input wrench ℱ<sub>i</sub> to sensor frame ℛ<sub>s</sub> | ||||||
|
||||||
Remarks : | ||||||
* a full vector is used for gravity force, to not impose gravity to be only along z of `world_frame`. | ||||||
* `data_in.frame` is usually equal to `sensor_frame`, but could be different since measurement of wrech might occur in another frame. Ex: 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 (thichkess of the sensor) to be accounted for. | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
* `data_out.frame` is usually `data_in.frame`, but for convenience, can be set to any other useful frame. Ex: Wrench expressed in a `control_frame` for instance center of a gripper. | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
* 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 ℛ<sub>w</sub> to ℛ<sub>s</sub>). |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Those changes should be removed.