#include <moveit_fake_controllers.h>

Public Member Functions | |
| InterpolatingController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
| ~InterpolatingController () | |
Public Member Functions inherited from moveit_fake_controller_manager::ThreadedController | |
| 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 | |
| virtual void | execTrajectory (const moveit_msgs::RobotTrajectory &t) |
Protected Member Functions inherited from moveit_fake_controller_manager::ThreadedController | |
| bool | cancelled () |
Private Attributes | |
| ros::WallRate | rate_ |
Additional Inherited Members | |
Protected Attributes inherited from moveit_fake_controller_manager::BaseFakeController | |
| std::vector< std::string > | joints_ |
| const ros::Publisher & | pub_ |
Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
| std::string | name_ |
Definition at line 113 of file moveit_fake_controllers.h.
| moveit_fake_controller_manager::InterpolatingController::InterpolatingController | ( | const std::string & | name, |
| const std::vector< std::string > & | joints, | ||
| const ros::Publisher & | pub | ||
| ) |
Definition at line 193 of file moveit_fake_controllers.cpp.
| moveit_fake_controller_manager::InterpolatingController::~InterpolatingController | ( | ) |
Definition at line 202 of file moveit_fake_controllers.cpp.
|
protectedvirtual |
Implements moveit_fake_controller_manager::ThreadedController.
Definition at line 224 of file moveit_fake_controllers.cpp.
|
private |
Definition at line 123 of file moveit_fake_controllers.h.