kinematic_extension_dof.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H
19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H
20 
21 #include <string>
22 #include <vector>
23 
24 #include <ros/ros.h>
25 #include <geometry_msgs/Twist.h>
26 #include <Eigen/Geometry>
27 
29 
30 /* BEGIN KinematicExtensionDOF ****************************************************************************************/
33 {
34  public:
36  : KinematicExtensionBase(params)
37  {}
38 
40 
41  virtual bool initExtension() = 0;
42  virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian& jac_chain) = 0;
43  virtual JointStates adjustJointStates(const JointStates& joint_states) = 0;
44  virtual LimiterParams adjustLimiterParams(const LimiterParams& limiter_params) = 0;
45  virtual void processResultExtension(const KDL::JntArray& q_dot_ik) = 0;
46 
47  KDL::Jacobian adjustJacobianDof(const KDL::Jacobian& jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim);
48 
49  protected:
50  unsigned int ext_dof_;
51  std::vector<std::string> joint_names_;
53  std::vector<double> limits_max_;
54  std::vector<double> limits_min_;
55  std::vector<double> limits_vel_;
56  std::vector<double> limits_acc_;
57 };
58 /* END KinematicExtensionDOF **********************************************************************************************/
59 
60 /* BEGIN KinematicExtensionBaseActive ****************************************************************************************/
63 {
64  public:
66  : KinematicExtensionDOF(params)
67  {}
68 
70 
71  bool initExtension();
72  KDL::Jacobian adjustJacobian(const KDL::Jacobian& jac_chain);
73  JointStates adjustJointStates(const JointStates& joint_states);
74  LimiterParams adjustLimiterParams(const LimiterParams& limiter_params);
75  void processResultExtension(const KDL::JntArray& q_dot_ik);
76 
77  void baseTwistCallback(const geometry_msgs::Twist::ConstPtr& msg);
78 
79  private:
81 
86 };
87 /* END KinematicExtensionBaseActive **********************************************************************************************/
88 
89 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_DOF_H
msg
Abstract Helper Class to be used for Cartesian KinematicExtensions based on enabled DoFs...
std::vector< std::string > joint_names_
std::vector< double > limits_max_
std::vector< double > limits_min_
virtual bool initExtension()=0
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)=0
virtual JointStates adjustJointStates(const JointStates &joint_states)=0
std::vector< double > limits_vel_
KDL::Jacobian adjustJacobianDof(const KDL::Jacobian &jac_chain, const KDL::Frame eb_frame_ct, const KDL::Frame cb_frame_eb, const ActiveCartesianDimension active_dim)
Base class for kinematic extensions.
Class implementing a mobile base KinematicExtension with Cartesian DoFs (lin_x, lin_y, rot_z) enabled (i.e. 2D).
std::vector< double > limits_acc_
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)=0
KinematicExtensionBaseActive(const TwistControllerParams &params)
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)=0
KinematicExtensionDOF(const TwistControllerParams &params)


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Thu Apr 8 2021 02:40:00