Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
moveit_fake_controller_manager::ThreadedController Class Reference

#include <moveit_fake_controllers.h>

Inheritance diagram for moveit_fake_controller_manager::ThreadedController:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 77 of file moveit_fake_controllers.h.


Constructor & Destructor Documentation

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.


Member Function Documentation

Definition at line 89 of file moveit_fake_controllers.h.

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]
bool moveit_fake_controller_manager::ThreadedController::sendTrajectory ( const moveit_msgs::RobotTrajectory &  t) [virtual]

Member Data Documentation

Definition at line 100 of file moveit_fake_controllers.h.

Definition at line 101 of file moveit_fake_controllers.h.

Definition at line 99 of file moveit_fake_controllers.h.


The documentation for this class was generated from the following files:


moveit_fake_controller_manager
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:22