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 () |
Class providing a ControllerInterface publishing a JointTrajectory.
Definition at line 70 of file controller_interface.h.
Definition at line 73 of file controller_interface.h.
Definition at line 74 of file controller_interface.h.
void cob_twist_controller::ControllerInterfaceTrajectory::initialize | ( | ros::NodeHandle & | nh, |
const TwistControllerParams & | params | ||
) | [virtual] |
Implements cob_twist_controller::ControllerInterfaceBase.
Definition at line 79 of file controller_interface.cpp.
void cob_twist_controller::ControllerInterfaceTrajectory::processResult | ( | const KDL::JntArray & | q_dot_ik, |
const KDL::JntArray & | current_q | ||
) | [inline, virtual] |
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.