Class providing a ControllerInterface publishing JointStates. More...
#include <controller_interface.h>

Public Member Functions | |
| ControllerInterfaceJointStates () | |
| virtual void | initialize (ros::NodeHandle &nh, const TwistControllerParams ¶ms) |
| virtual void | processResult (const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q) |
| ~ControllerInterfaceJointStates () | |
Public Member Functions inherited from cob_twist_controller::ControllerInterfacePositionBase | |
| bool | updateIntegration (const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_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< SimpsonIntegrator > | integrator_ |
| 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_ |
Class providing a ControllerInterface publishing JointStates.
Definition at line 85 of file controller_interface.h.
|
inline |
Definition at line 88 of file controller_interface.h.
|
inline |
Definition at line 89 of file controller_interface.h.
|
virtual |
Implements cob_twist_controller::ControllerInterfaceBase.
Definition at line 116 of file controller_interface.cpp.
|
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.
|
private |
Timer callback publishing the internal JointState to the 'joint_state' topic.
Definition at line 176 of file controller_interface.cpp.
|
private |
Definition at line 98 of file controller_interface.h.
|
private |
Definition at line 100 of file controller_interface.h.
|
private |
Definition at line 97 of file controller_interface.h.