00001 /* 00002 * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA) 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 */ 00016 00017 00018 #ifndef COB_TWIST_CONTROLLER_LIMITERS_LIMITER_H 00019 #define COB_TWIST_CONTROLLER_LIMITERS_LIMITER_H 00020 00021 #include <vector> 00022 00023 #include "cob_twist_controller/limiters/limiter_base.h" 00024 00025 #define LIMIT_SAFETY_THRESHOLD 0.1/180.0*M_PI 00026 00027 /* BEGIN LimiterJointContainer *******************************************************************************/ 00029 class LimiterContainer 00030 { 00031 public: 00036 virtual KDL::Twist enforceLimits(const KDL::Twist& v_in) const; 00037 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00038 00042 void init(); 00043 00044 virtual ~LimiterContainer(); 00045 00046 explicit LimiterContainer(const LimiterParams& limiter_params) : 00047 limiter_params_(limiter_params) 00048 {} 00049 00050 protected: 00051 const LimiterParams& limiter_params_; 00052 00053 std::vector<const LimiterCartesianBase*> input_limiters_; 00054 std::vector<const LimiterJointBase*> output_limiters_; 00055 typedef std::vector<const LimiterCartesianBase*>::const_iterator input_LimIter_t; 00056 typedef std::vector<const LimiterJointBase*>::const_iterator output_LimIter_t; 00057 00062 void add(const LimiterCartesianBase* lb); 00063 void add(const LimiterJointBase* lb); 00064 00068 void eraseAll(); 00069 }; 00070 /* END LimiterJointContainer *****************************************************************************************/ 00071 00072 /* BEGIN LimiterAllJointPositions *******************************************************************************/ 00074 class LimiterAllJointPositions : public LimiterJointBase 00075 { 00076 public: 00081 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00082 00083 explicit LimiterAllJointPositions(const LimiterParams& limiter_params) : 00084 LimiterJointBase(limiter_params) 00085 {} 00086 }; 00087 /* END LimiterAllJointPositions **********************************************************************************/ 00088 00089 /* BEGIN LimiterAllJointVelocities *******************************************************************************/ 00091 class LimiterAllJointVelocities : public LimiterJointBase 00092 { 00093 public: 00098 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00099 00100 explicit LimiterAllJointVelocities(const LimiterParams& limiter_params) : 00101 LimiterJointBase(limiter_params) 00102 {} 00103 }; 00104 /* END LimiterAllJointVelocities *********************************************************************************/ 00105 00106 /* BEGIN LimiterAllJointAccelerations ****************************************************************************/ 00108 class LimiterAllJointAccelerations : public LimiterJointBase 00109 { 00110 public: 00115 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00116 00117 explicit LimiterAllJointAccelerations(const LimiterParams& limiter_params) : 00118 LimiterJointBase(limiter_params) 00119 {} 00120 }; 00121 /* END LimiterAllJointAccelerations ******************************************************************************/ 00122 00123 /* BEGIN LimiterAllCartesianVelocities ***********************************************************************/ 00125 class LimiterAllCartesianVelocities : public LimiterCartesianBase 00126 { 00127 public: 00132 virtual KDL::Twist enforceLimits(const KDL::Twist& v_in) const; 00133 00134 explicit LimiterAllCartesianVelocities(const LimiterParams& limiter_params) : 00135 LimiterCartesianBase(limiter_params) 00136 {} 00137 }; 00138 /* END LimiterAllCartesianVelocities *************************************************************************/ 00139 00140 /* BEGIN LimiterIndividualJointPositions *************************************************************************/ 00142 class LimiterIndividualJointPositions : public LimiterJointBase 00143 { 00144 public: 00149 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00150 00151 explicit LimiterIndividualJointPositions(const LimiterParams& limiter_params) : 00152 LimiterJointBase(limiter_params) 00153 {} 00154 }; 00155 /* END LimiterIndividualJointPositions **************************************************************************/ 00156 00157 /* BEGIN LimiterIndividualJointVelocities ***********************************************************************/ 00159 class LimiterIndividualJointVelocities : public LimiterJointBase 00160 { 00161 public: 00166 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00167 00168 explicit LimiterIndividualJointVelocities(const LimiterParams& limiter_params) : 00169 LimiterJointBase(limiter_params) 00170 {} 00171 }; 00172 /* END LimiterIndividualJointVelocities *************************************************************************/ 00173 00174 /* BEGIN LimiterIndividualJointAccelerations ***********************************************************************/ 00176 class LimiterIndividualJointAccelerations : public LimiterJointBase 00177 { 00178 public: 00183 virtual KDL::JntArray enforceLimits(const KDL::JntArray& q_dot_ik, const KDL::JntArray& q) const; 00184 00185 explicit LimiterIndividualJointAccelerations(const LimiterParams& limiter_params) : 00186 LimiterJointBase(limiter_params) 00187 {} 00188 }; 00189 /* END LimiterIndividualJointAccelerations *************************************************************************/ 00190 00191 /* BEGIN LimiterIndividualCartesianVelocities ***********************************************************************/ 00193 class LimiterIndividualCartesianVelocities : public LimiterCartesianBase 00194 { 00195 public: 00200 virtual KDL::Twist enforceLimits(const KDL::Twist& v_in) const; 00201 00202 explicit LimiterIndividualCartesianVelocities(const LimiterParams& limiter_params) : 00203 LimiterCartesianBase(limiter_params) 00204 {} 00205 }; 00206 /* END LimiterIndividualCartesianVelocities *************************************************************************/ 00207 00208 #endif // COB_TWIST_CONTROLLER_LIMITERS_LIMITER_H