Public Member Functions | Protected Attributes | List of all members
moveit_fake_controller_manager::BaseFakeController Class Reference

#include <moveit_fake_controllers.h>

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

Public Member Functions

 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
virtual bool cancelExecution ()=0
 
const std::string & getName () const
 
 MoveItControllerHandle (const std::string &name)
 
virtual bool sendTrajectory (const moveit_msgs::RobotTrajectory &trajectory)=0
 
virtual bool waitForExecution (const ros::Duration &timeout=ros::Duration(0))=0
 
virtual ~MoveItControllerHandle ()
 

Protected Attributes

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

Detailed Description

Definition at line 52 of file moveit_fake_controllers.h.

Constructor & Destructor Documentation

moveit_fake_controller_manager::BaseFakeController::BaseFakeController ( const std::string &  name,
const std::vector< std::string > &  joints,
const ros::Publisher pub 
)

Definition at line 46 of file moveit_fake_controllers.cpp.

Member Function Documentation

void moveit_fake_controller_manager::BaseFakeController::getJoints ( std::vector< std::string > &  joints) const

Definition at line 57 of file moveit_fake_controllers.cpp.

moveit_controller_manager::ExecutionStatus moveit_fake_controller_manager::BaseFakeController::getLastExecutionStatus ( )
virtual

Member Data Documentation

std::vector<std::string> moveit_fake_controller_manager::BaseFakeController::joints_
protected

Definition at line 61 of file moveit_fake_controllers.h.

const ros::Publisher& moveit_fake_controller_manager::BaseFakeController::pub_
protected

Definition at line 62 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