Public Member Functions | Private Member Functions | Private Attributes | List of all members
cob_twist_controller::ControllerInterfaceJointStates Class Reference

Class providing a ControllerInterface publishing JointStates. More...

#include <controller_interface.h>

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

Public Member Functions

 ControllerInterfaceJointStates ()
 
virtual void initialize (ros::NodeHandle &nh, const TwistControllerParams &params)
 
virtual void processResult (const KDL::JntArray &q_dot_ik, const KDL::JntArray &current_q)
 
 ~ControllerInterfaceJointStates ()
 
- 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 ()
 

Private Member Functions

void publishJointState (const ros::TimerEvent &event)
 

Private Attributes

sensor_msgs::JointState js_msg_
 
ros::Timer js_timer_
 
boost::mutex mutex_
 

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 JointStates.

Definition at line 85 of file controller_interface.h.

Constructor & Destructor Documentation

cob_twist_controller::ControllerInterfaceJointStates::ControllerInterfaceJointStates ( )
inline

Definition at line 88 of file controller_interface.h.

cob_twist_controller::ControllerInterfaceJointStates::~ControllerInterfaceJointStates ( )
inline

Definition at line 89 of file controller_interface.h.

Member Function Documentation

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

Method processing the result using integration method (Simpson) updating the internal JointState.

update JointState

publishing takes place in separate thread

Implements cob_twist_controller::ControllerInterfaceBase.

Definition at line 159 of file controller_interface.cpp.

void cob_twist_controller::ControllerInterfaceJointStates::publishJointState ( const ros::TimerEvent event)
private

Timer callback publishing the internal JointState to the 'joint_state' topic.

Definition at line 176 of file controller_interface.cpp.

Member Data Documentation

sensor_msgs::JointState cob_twist_controller::ControllerInterfaceJointStates::js_msg_
private

Definition at line 98 of file controller_interface.h.

ros::Timer cob_twist_controller::ControllerInterfaceJointStates::js_timer_
private

Definition at line 100 of file controller_interface.h.

boost::mutex cob_twist_controller::ControllerInterfaceJointStates::mutex_
private

Definition at line 97 of file controller_interface.h.


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