Go to the documentation of this file.
18 #ifndef COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_BASE_H
19 #define COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_BASE_H
39 const KDL::JntArray& current_q) = 0;
56 const KDL::JntArray& current_q)
75 #endif // COB_TWIST_CONTROLLER_CONTROLLER_INTERFACES_CONTROLLER_INTERFACE_BASE_H
virtual ~ControllerInterfaceBase()
std::vector< double > pos_
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)=0
Base class for controller interfaces.
boost::shared_ptr< SimpsonIntegrator > integrator_
ControllerInterfaceBase()
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams ¶ms)=0
Base class for controller interfaces using position integration.
ControllerInterfacePositionBase()
ros::Time last_update_time_
bool updateIntegration(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
~ControllerInterfacePositionBase()
TwistControllerParams params_
std::vector< double > vel_
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43