|
| 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_ |
0 commit comments