Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
moveit_fake_controller_manager::ThreadedController Class Referenceabstract

#include <moveit_fake_controllers.h>

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

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 ()
 
- 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
 
- Public Member Functions inherited from moveit_controller_manager::MoveItControllerHandle
const std::string & getName () const
 
 MoveItControllerHandle (const std::string &name)
 
virtual ~MoveItControllerHandle ()
 

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_
 

Additional Inherited Members

- Protected Attributes inherited from moveit_fake_controller_manager::BaseFakeController
std::vector< std::string > joints_
 
const ros::Publisherpub_
 
- Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle
std::string name_
 

Detailed Description

Definition at line 76 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.

moveit_fake_controller_manager::ThreadedController::~ThreadedController ( )

Definition at line 113 of file moveit_fake_controllers.cpp.

Member Function Documentation

bool moveit_fake_controller_manager::ThreadedController::cancelExecution ( )
virtual
bool moveit_fake_controller_manager::ThreadedController::cancelled ( )
inlineprotected

Definition at line 88 of file moveit_fake_controllers.h.

void moveit_fake_controller_manager::ThreadedController::cancelTrajectory ( )
privatevirtual

Definition at line 118 of file moveit_fake_controllers.cpp.

virtual void moveit_fake_controller_manager::ThreadedController::execTrajectory ( const moveit_msgs::RobotTrajectory &  t)
privatepure virtual
moveit_controller_manager::ExecutionStatus moveit_fake_controller_manager::ThreadedController::getLastExecutionStatus ( )
virtual
bool moveit_fake_controller_manager::ThreadedController::sendTrajectory ( const moveit_msgs::RobotTrajectory &  t)
virtual
bool moveit_fake_controller_manager::ThreadedController::waitForExecution ( const ros::Duration )
virtual

Member Data Documentation

bool moveit_fake_controller_manager::ThreadedController::cancel_
private

Definition at line 99 of file moveit_fake_controllers.h.

moveit_controller_manager::ExecutionStatus moveit_fake_controller_manager::ThreadedController::status_
private

Definition at line 100 of file moveit_fake_controllers.h.

boost::thread moveit_fake_controller_manager::ThreadedController::thread_
private

Definition at line 98 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 Jul 10 2019 04:03:39