Go to the documentation of this file.
18 #ifndef COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H
19 #define COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H
26 #include <boost/shared_ptr.hpp>
27 #include <boost/thread/mutex.hpp>
29 #include <kdl/chainjnttojacsolver.hpp>
30 #include <kdl/chainfksolverpos_recursive.hpp>
33 #include <Eigen/Geometry>
50 virtual KDL::Jacobian
adjustJacobian(
const KDL::Jacobian& jac_chain);
78 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
std::vector< double > limits_ext_vel_
Base class for kinematic extensions.
Class to be used for Cartesian KinematicExtensions for Lookat.
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
void broadcastFocusFrame(const ros::TimerEvent &event)
tf::TransformBroadcaster br_
std::vector< double > limits_ext_min_
std::vector< double > limits_ext_acc_
boost::shared_ptr< KDL::ChainJntToJacSolver > jnt2jac_
KinematicExtensionLookat(const TwistControllerParams ¶ms)
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
boost::shared_ptr< SimpsonIntegrator > integrator_
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_ext_
std::vector< double > limits_ext_max_
JointStates joint_states_ext_
JointStates joint_states_full_
~KinematicExtensionLookat()
virtual JointStates adjustJointStates(const JointStates &joint_states)
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43