Public Member Functions | List of all members
cob_twist_controller::ControllerInterfaceTrajectory Class Reference

Class providing a ControllerInterface publishing a JointTrajectory. More...

#include <controller_interface.h>

Inheritance diagram for cob_twist_controller::ControllerInterfaceTrajectory:
Inheritance graph
[legend]

Public Member Functions

 ControllerInterfaceTrajectory ()
 
virtual void initialize (ros::NodeHandle &nh, const TwistControllerParams &params)
 
virtual void processResult (const KDL::JntArray &q_dot_ik, const KDL::JntArray &current_q)
 
 ~ControllerInterfaceTrajectory ()
 
- Public Member Functions inherited from cob_twist_controller::ControllerInterfacePositionBase
bool updateIntegration (const KDL::JntArray &q_dot_ik, const KDL::JntArray &current_q)
 
 ~ControllerInterfacePositionBase ()
 
- Public Member Functions inherited from cob_twist_controller::ControllerInterfaceBase
virtual ~ControllerInterfaceBase ()
 

Additional Inherited Members

- Protected Member Functions inherited from cob_twist_controller::ControllerInterfacePositionBase
 ControllerInterfacePositionBase ()
 
- Protected Member Functions inherited from cob_twist_controller::ControllerInterfaceBase
 ControllerInterfaceBase ()
 
- Protected Attributes inherited from cob_twist_controller::ControllerInterfacePositionBase
boost::shared_ptr< SimpsonIntegratorintegrator_
 
ros::Time last_update_time_
 
ros::Duration period_
 
std::vector< double > pos_
 
std::vector< double > vel_
 
- Protected Attributes inherited from cob_twist_controller::ControllerInterfaceBase
ros::NodeHandle nh_
 
TwistControllerParams params_
 
ros::Publisher pub_
 

Detailed Description

Class providing a ControllerInterface publishing a JointTrajectory.

Definition at line 70 of file controller_interface.h.

Constructor & Destructor Documentation

cob_twist_controller::ControllerInterfaceTrajectory::ControllerInterfaceTrajectory ( )
inline

Definition at line 73 of file controller_interface.h.

cob_twist_controller::ControllerInterfaceTrajectory::~ControllerInterfaceTrajectory ( )
inline

Definition at line 74 of file controller_interface.h.

Member Function Documentation

void cob_twist_controller::ControllerInterfaceTrajectory::initialize ( ros::NodeHandle nh,
const TwistControllerParams params 
)
virtual
void cob_twist_controller::ControllerInterfaceTrajectory::processResult ( const KDL::JntArray q_dot_ik,
const KDL::JntArray current_q 
)
inlinevirtual

Method processing the result using integration method (Simpson) and publishing to the 'joint_trajectory_controller/command' topic.

publish to interface

Implements cob_twist_controller::ControllerInterfaceBase.

Definition at line 91 of file controller_interface.cpp.


The documentation for this class was generated from the following files:


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