#include <moveit_fake_controllers.h>

| Public Member Functions | |
| virtual bool | cancelExecution () | 
| LastPointController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
| virtual bool | sendTrajectory (const moveit_msgs::RobotTrajectory &t) | 
| virtual bool | waitForExecution (const ros::Duration &) | 
| ~LastPointController () | |
|  Public Member Functions inherited from moveit_fake_controller_manager::BaseFakeController | |
| BaseFakeController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
| void | getJoints (std::vector< std::string > &joints) const | 
| virtual moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () | 
|  Public Member Functions inherited from moveit_controller_manager::MoveItControllerHandle | |
| const std::string & | getName () const | 
| MoveItControllerHandle (const std::string &name) | |
| virtual | ~MoveItControllerHandle () | 
| Additional Inherited Members | |
|  Protected Attributes inherited from moveit_fake_controller_manager::BaseFakeController | |
| std::vector< std::string > | joints_ | 
| const ros::Publisher & | pub_ | 
|  Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
| std::string | name_ | 
Definition at line 65 of file moveit_fake_controllers.h.
| moveit_fake_controller_manager::LastPointController::LastPointController | ( | const std::string & | name, | 
| const std::vector< std::string > & | joints, | ||
| const ros::Publisher & | pub | ||
| ) | 
Definition at line 67 of file moveit_fake_controllers.cpp.
| moveit_fake_controller_manager::LastPointController::~LastPointController | ( | ) | 
Definition at line 73 of file moveit_fake_controllers.cpp.
| 
 | virtual | 
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 96 of file moveit_fake_controllers.cpp.
| 
 | virtual | 
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 77 of file moveit_fake_controllers.cpp.
| 
 | virtual | 
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 101 of file moveit_fake_controllers.cpp.