42 #include <boost/thread/thread.hpp> 44 #ifndef MOVEIT_FAKE_CONTROLLERS 45 #define MOVEIT_FAKE_CONTROLLERS 58 void getJoints(std::vector<std::string>& joints)
const;
71 virtual bool sendTrajectory(
const moveit_msgs::RobotTrajectory& t);
82 virtual bool sendTrajectory(
const moveit_msgs::RobotTrajectory& t);
94 virtual void execTrajectory(
const moveit_msgs::RobotTrajectory& t) = 0;
95 virtual void cancelTrajectory();
110 virtual void execTrajectory(
const moveit_msgs::RobotTrajectory& t);
120 virtual void execTrajectory(
const moveit_msgs::RobotTrajectory& t);
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
MOVEIT_CLASS_FORWARD(BaseFakeController)
void getJoints(std::vector< std::string > &joints) const
virtual bool cancelExecution()=0
std::vector< std::string > joints_
virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)=0
const ros::Publisher & pub_
virtual bool waitForExecution(const ros::Duration &timeout=ros::Duration(0))=0
moveit_controller_manager::ExecutionStatus status_