kinematic_extension_lookat.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_LOOKAT_H
19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H
20 
21 #include <string>
22 #include <vector>
23 #include <limits>
24 #include <ros/ros.h>
25 
26 #include <boost/shared_ptr.hpp>
27 #include <boost/thread/mutex.hpp>
29 #include <kdl/chainjnttojacsolver.hpp>
30 #include <kdl/chainfksolverpos_recursive.hpp>
31 #include <tf_conversions/tf_kdl.h>
33 #include <Eigen/Geometry>
34 
37 
38 /* BEGIN KinematicExtensionLookat ****************************************************************************************/
41 {
42  public:
44  : KinematicExtensionBase(params)
45  {}
46 
48 
49  bool initExtension();
50  virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian& jac_chain);
51  virtual JointStates adjustJointStates(const JointStates& joint_states);
52  virtual LimiterParams adjustLimiterParams(const LimiterParams& limiter_params);
53  virtual void processResultExtension(const KDL::JntArray& q_dot_ik);
54 
55  private:
56  unsigned int ext_dof_;
57  KDL::Chain chain_ext_;
58  KDL::Chain chain_full_;
61  std::vector<double> limits_ext_max_;
62  std::vector<double> limits_ext_min_;
63  std::vector<double> limits_ext_vel_;
64  std::vector<double> limits_ext_acc_;
65 
68 
70 
71  boost::mutex mutex_;
74  void broadcastFocusFrame(const ros::TimerEvent& event);
75 };
76 /* END KinematicExtensionLookat **********************************************************************************************/
77 
78 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H
KinematicExtensionLookat::adjustLimiterParams
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
Definition: kinematic_extension_lookat.cpp:199
KinematicExtensionLookat::timer_
ros::Timer timer_
Definition: kinematic_extension_lookat.h:72
KinematicExtensionLookat::limits_ext_vel_
std::vector< double > limits_ext_vel_
Definition: kinematic_extension_lookat.h:63
KinematicExtensionBase
Base class for kinematic extensions.
Definition: kinematic_extension_base.h:28
KinematicExtensionLookat
Class to be used for Cartesian KinematicExtensions for Lookat.
Definition: kinematic_extension_lookat.h:40
KinematicExtensionLookat::adjustJacobian
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
Definition: kinematic_extension_lookat.cpp:161
boost::shared_ptr< KDL::ChainJntToJacSolver >
KinematicExtensionLookat::mutex_
boost::mutex mutex_
Definition: kinematic_extension_lookat.h:71
kinematic_extension_base.h
KinematicExtensionLookat::broadcastFocusFrame
void broadcastFocusFrame(const ros::TimerEvent &event)
Definition: kinematic_extension_lookat.cpp:236
ros.h
KinematicExtensionLookat::chain_ext_
KDL::Chain chain_ext_
Definition: kinematic_extension_lookat.h:57
KinematicExtensionLookat::br_
tf::TransformBroadcaster br_
Definition: kinematic_extension_lookat.h:73
KinematicExtensionLookat::initExtension
bool initExtension()
Definition: kinematic_extension_lookat.cpp:27
transform_broadcaster.h
KinematicExtensionLookat::limits_ext_min_
std::vector< double > limits_ext_min_
Definition: kinematic_extension_lookat.h:62
KinematicExtensionLookat::ext_dof_
unsigned int ext_dof_
Definition: kinematic_extension_lookat.h:56
KinematicExtensionLookat::limits_ext_acc_
std::vector< double > limits_ext_acc_
Definition: kinematic_extension_lookat.h:64
KinematicExtensionLookat::jnt2jac_
boost::shared_ptr< KDL::ChainJntToJacSolver > jnt2jac_
Definition: kinematic_extension_lookat.h:66
simpson_integrator.h
tf::TransformBroadcaster
KinematicExtensionLookat::KinematicExtensionLookat
KinematicExtensionLookat(const TwistControllerParams &params)
Definition: kinematic_extension_lookat.h:43
KinematicExtensionLookat::processResultExtension
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
Definition: kinematic_extension_lookat.cpp:212
ros::TimerEvent
kdl_parser.hpp
KinematicExtensionLookat::chain_full_
KDL::Chain chain_full_
Definition: kinematic_extension_lookat.h:58
LimiterParams
Definition: cob_twist_controller_data_types.h:162
KinematicExtensionLookat::integrator_
boost::shared_ptr< SimpsonIntegrator > integrator_
Definition: kinematic_extension_lookat.h:69
KinematicExtensionLookat::fk_solver_ext_
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_ext_
Definition: kinematic_extension_lookat.h:67
tf_kdl.h
KinematicExtensionLookat::limits_ext_max_
std::vector< double > limits_ext_max_
Definition: kinematic_extension_lookat.h:61
TwistControllerParams
Definition: cob_twist_controller_data_types.h:209
JointStates
Definition: cob_twist_controller_data_types.h:112
KinematicExtensionLookat::joint_states_ext_
JointStates joint_states_ext_
Definition: kinematic_extension_lookat.h:59
ros::Timer
KinematicExtensionLookat::joint_states_full_
JointStates joint_states_full_
Definition: kinematic_extension_lookat.h:60
KinematicExtensionLookat::~KinematicExtensionLookat
~KinematicExtensionLookat()
Definition: kinematic_extension_lookat.h:47
KinematicExtensionLookat::adjustJointStates
virtual JointStates adjustJointStates(const JointStates &joint_states)
Definition: kinematic_extension_lookat.cpp:172


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43