#include <effort_test_controller.h>

Public Member Functions | |
| EffortTestController () | |
| bool | init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n) |
| void | starting (const ros::Time &time) |
| void | stopping (const ros::Time &time) |
| void | update (const ros::Time &time, const ros::Duration &period) |
Private Attributes | |
| std::vector < hardware_interface::JointHandle > | joint_effort_commands_ |
Definition at line 41 of file effort_test_controller.h.
Definition at line 44 of file effort_test_controller.h.
| bool EffortTestController::init | ( | hardware_interface::EffortJointInterface * | hw, |
| ros::NodeHandle & | n | ||
| ) | [virtual] |
Reimplemented from controller_interface::Controller< hardware_interface::EffortJointInterface >.
Definition at line 33 of file effort_test_controller.cpp.
| void EffortTestController::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 49 of file effort_test_controller.cpp.
| void EffortTestController::stopping | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 62 of file effort_test_controller.cpp.
| void EffortTestController::update | ( | const ros::Time & | time, |
| const ros::Duration & | period | ||
| ) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 54 of file effort_test_controller.cpp.
std::vector<hardware_interface::JointHandle> controller_manager_tests::EffortTestController::joint_effort_commands_ [private] |
Definition at line 52 of file effort_test_controller.h.