|
| 1 | +// Copyright (c) 2021, 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 | +/// \author Denis Stogl |
| 16 | + |
| 17 | +#ifndef JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_ |
| 18 | +#define JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_ |
| 19 | + |
| 20 | +#include <string> |
| 21 | +#include <vector> |
| 22 | + |
| 23 | +#include "joint_limits/joint_limits.hpp" |
| 24 | +#include "joint_limits/visibility_control.h" |
| 25 | +#include "rclcpp/node.hpp" |
| 26 | +#include "trajectory_msgs/msg/joint_trajectory_point.hpp" |
| 27 | + |
| 28 | +namespace joint_limits |
| 29 | +{ |
| 30 | +template <typename LimitsType> |
| 31 | +class JointLimiterInterface |
| 32 | +{ |
| 33 | +public: |
| 34 | + JOINT_LIMITS_PUBLIC JointLimiterInterface() = default; |
| 35 | + |
| 36 | + JOINT_LIMITS_PUBLIC virtual ~JointLimiterInterface() = default; |
| 37 | + |
| 38 | + /// Initialization of every JointLimiter. |
| 39 | + /** |
| 40 | + * Initialization of JointLimiter for defined joints with their names. |
| 41 | + * Robot description topic provides a topic name where URDF of the robot can be found. |
| 42 | + * This is needed to use joint limits from URDF (not implemented yet!). |
| 43 | + * Override this method only if Initialization and reading joint limits should be adapted. |
| 44 | + * Otherwise, initialize your custom limiter in `on_limit` method. |
| 45 | + * |
| 46 | + * \param[in] joint_names names of joints where limits should be applied. |
| 47 | + * \param[in] node shared pointer to the node where joint limit parameters defined. |
| 48 | + * \param[in] robot_description_topic string of a topic where robot description is accessible. |
| 49 | + * |
| 50 | + */ |
| 51 | + JOINT_LIMITS_PUBLIC virtual bool init( |
| 52 | + const std::vector<std::string> joint_names, const rclcpp::Node::SharedPtr & node, |
| 53 | + const std::string & robot_description_topic = "/robot_description"); |
| 54 | + |
| 55 | + JOINT_LIMITS_PUBLIC virtual bool configure( |
| 56 | + const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states) |
| 57 | + { |
| 58 | + return on_configure(current_joint_states); |
| 59 | + } |
| 60 | + |
| 61 | + JOINT_LIMITS_PUBLIC virtual bool enforce( |
| 62 | + trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states, |
| 63 | + trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states, const rclcpp::Duration & dt) |
| 64 | + { |
| 65 | + // TODO(destogl): add checks if sizes of vectors and number of limits correspond. |
| 66 | + return on_enforce(current_joint_states, desired_joint_states, dt); |
| 67 | + } |
| 68 | + |
| 69 | + // TODO(destogl): Make those protected? |
| 70 | + // Methods that each limiter implementation has to implement |
| 71 | + JOINT_LIMITS_PUBLIC virtual bool on_init() { return true; } |
| 72 | + |
| 73 | + JOINT_LIMITS_PUBLIC virtual bool on_configure( |
| 74 | + const trajectory_msgs::msg::JointTrajectoryPoint & /*current_joint_states*/) |
| 75 | + { |
| 76 | + return true; |
| 77 | + } |
| 78 | + |
| 79 | + JOINT_LIMITS_PUBLIC virtual bool on_enforce( |
| 80 | + trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states, |
| 81 | + trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states, |
| 82 | + const rclcpp::Duration & dt) = 0; |
| 83 | + |
| 84 | +protected: |
| 85 | + size_t number_of_joints_; |
| 86 | + std::vector<LimitsType> joint_limits_; |
| 87 | + rclcpp::Node::SharedPtr node_; |
| 88 | +}; |
| 89 | + |
| 90 | +} // namespace joint_limits |
| 91 | + |
| 92 | +#endif // JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_ |
0 commit comments