#include <moveit_fake_controllers.h>

Public Member Functions | |
| virtual bool | cancelExecution () |
| virtual moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () |
| virtual bool | sendTrajectory (const moveit_msgs::RobotTrajectory &t) |
| ThreadedController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
| virtual bool | waitForExecution (const ros::Duration &) |
| ~ThreadedController () | |
Protected Member Functions | |
| bool | cancelled () |
Private Member Functions | |
| virtual void | cancelTrajectory () |
| virtual void | execTrajectory (const moveit_msgs::RobotTrajectory &t)=0 |
Private Attributes | |
| bool | cancel_ |
| moveit_controller_manager::ExecutionStatus | status_ |
| boost::thread | thread_ |
Definition at line 77 of file moveit_fake_controllers.h.
| moveit_fake_controller_manager::ThreadedController::ThreadedController | ( | const std::string & | name, |
| const std::vector< std::string > & | joints, | ||
| const ros::Publisher & | pub | ||
| ) |
Definition at line 107 of file moveit_fake_controllers.cpp.
Definition at line 113 of file moveit_fake_controllers.cpp.
| bool moveit_fake_controller_manager::ThreadedController::cancelExecution | ( | ) | [virtual] |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 133 of file moveit_fake_controllers.cpp.
| bool moveit_fake_controller_manager::ThreadedController::cancelled | ( | ) | [inline, protected] |
Definition at line 89 of file moveit_fake_controllers.h.
| void moveit_fake_controller_manager::ThreadedController::cancelTrajectory | ( | ) | [private, virtual] |
Definition at line 118 of file moveit_fake_controllers.cpp.
| virtual void moveit_fake_controller_manager::ThreadedController::execTrajectory | ( | const moveit_msgs::RobotTrajectory & | t | ) | [private, pure virtual] |
| moveit_controller_manager::ExecutionStatus moveit_fake_controller_manager::ThreadedController::getLastExecutionStatus | ( | ) | [virtual] |
Reimplemented from moveit_fake_controller_manager::BaseFakeController.
Definition at line 148 of file moveit_fake_controllers.cpp.
| bool moveit_fake_controller_manager::ThreadedController::sendTrajectory | ( | const moveit_msgs::RobotTrajectory & | t | ) | [virtual] |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 124 of file moveit_fake_controllers.cpp.
| bool moveit_fake_controller_manager::ThreadedController::waitForExecution | ( | const ros::Duration & | ) | [virtual] |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 141 of file moveit_fake_controllers.cpp.
bool moveit_fake_controller_manager::ThreadedController::cancel_ [private] |
Definition at line 100 of file moveit_fake_controllers.h.
moveit_controller_manager::ExecutionStatus moveit_fake_controller_manager::ThreadedController::status_ [private] |
Definition at line 101 of file moveit_fake_controllers.h.
boost::thread moveit_fake_controller_manager::ThreadedController::thread_ [private] |
Definition at line 99 of file moveit_fake_controllers.h.