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> 78 #endif // COB_TWIST_CONTROLLER_KINEMATIC_EXTENSIONS_KINEMATIC_EXTENSION_LOOKAT_H ~KinematicExtensionLookat()
virtual KDL::Jacobian adjustJacobian(const KDL::Jacobian &jac_chain)
boost::shared_ptr< KDL::ChainJntToJacSolver > jnt2jac_
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > fk_solver_ext_
Class to be used for Cartesian KinematicExtensions for Lookat.
std::vector< double > limits_ext_vel_
std::vector< double > limits_ext_min_
Base class for kinematic extensions.
tf::TransformBroadcaster br_
std::vector< double > limits_ext_max_
boost::shared_ptr< SimpsonIntegrator > integrator_
KinematicExtensionLookat(const TwistControllerParams ¶ms)
JointStates joint_states_full_
virtual void processResultExtension(const KDL::JntArray &q_dot_ik)
JointStates joint_states_ext_
virtual LimiterParams adjustLimiterParams(const LimiterParams &limiter_params)
std::vector< double > limits_ext_acc_
virtual JointStates adjustJointStates(const JointStates &joint_states)
void broadcastFocusFrame(const ros::TimerEvent &event)