Class providing a ControllerInterface publishing a JointTrajectory. More...
#include <controller_interface.h>
Public Member Functions | |
ControllerInterfaceTrajectory () | |
virtual void | initialize (ros::NodeHandle &nh, const TwistControllerParams ¶ms) |
virtual void | processResult (const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q) |
~ControllerInterfaceTrajectory () | |
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 () |
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 a JointTrajectory.
Definition at line 70 of file controller_interface.h.
|
inline |
Definition at line 73 of file controller_interface.h.
|
inline |
Definition at line 74 of file controller_interface.h.
|
virtual |
Implements cob_twist_controller::ControllerInterfaceBase.
Definition at line 79 of file controller_interface.cpp.
|
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.