#include <moveit_fake_controllers.h>
Definition at line 109 of file moveit_fake_controllers.h.
◆ ThreadedController()
moveit_fake_controller_manager::ThreadedController::ThreadedController |
( |
const std::string & |
name, |
|
|
const std::vector< std::string > & |
joints, |
|
|
const ros::Publisher & |
pub |
|
) |
| |
◆ ~ThreadedController()
moveit_fake_controller_manager::ThreadedController::~ThreadedController |
( |
| ) |
|
|
override |
◆ cancelExecution()
bool moveit_fake_controller_manager::ThreadedController::cancelExecution |
( |
| ) |
|
|
overridevirtual |
◆ cancelled()
bool moveit_fake_controller_manager::ThreadedController::cancelled |
( |
| ) |
|
|
inlineprotected |
◆ cancelTrajectory()
void moveit_fake_controller_manager::ThreadedController::cancelTrajectory |
( |
| ) |
|
|
privatevirtual |
◆ execTrajectory()
virtual void moveit_fake_controller_manager::ThreadedController::execTrajectory |
( |
const moveit_msgs::RobotTrajectory & |
t | ) |
|
|
privatepure virtual |
◆ getLastExecutionStatus()
◆ sendTrajectory()
bool moveit_fake_controller_manager::ThreadedController::sendTrajectory |
( |
const moveit_msgs::RobotTrajectory & |
t | ) |
|
|
overridevirtual |
◆ waitForExecution()
bool moveit_fake_controller_manager::ThreadedController::waitForExecution |
( |
const ros::Duration & |
| ) |
|
|
overridevirtual |
◆ cancel_
bool moveit_fake_controller_manager::ThreadedController::cancel_ |
|
private |
◆ status_
◆ thread_
boost::thread moveit_fake_controller_manager::ThreadedController::thread_ |
|
private |
The documentation for this class was generated from the following files: