#include <moveit_fake_controllers.h>
Public Member Functions | |
InterpolatingController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
~InterpolatingController () override | |
![]() | |
bool | cancelExecution () override |
moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () override |
bool | sendTrajectory (const moveit_msgs::RobotTrajectory &t) override |
ThreadedController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
bool | waitForExecution (const ros::Duration &) override |
~ThreadedController () override | |
![]() | |
BaseFakeController (const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub) | |
void | getJoints (std::vector< std::string > &joints) const |
![]() | |
const std::string & | getName () const |
MoveItControllerHandle (const std::string &name) | |
virtual | ~MoveItControllerHandle () |
Protected Member Functions | |
void | execTrajectory (const moveit_msgs::RobotTrajectory &t) override |
![]() | |
bool | cancelled () |
Private Attributes | |
ros::WallRate | rate_ |
Additional Inherited Members | |
![]() | |
std::vector< std::string > | joints_ |
const ros::Publisher & | pub_ |
![]() | |
std::string | name_ |
Definition at line 146 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 222 of file moveit_fake_controllers.cpp.
|
overridedefault |
|
overrideprotectedvirtual |
Implements moveit_fake_controller_manager::ThreadedController.
Definition at line 251 of file moveit_fake_controllers.cpp.
|
private |
Definition at line 156 of file moveit_fake_controllers.h.