Go to the documentation of this file.
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;
61 std::vector<std::string>
joints_;
65 class LastPointController :
public BaseFakeController
71 bool sendTrajectory(
const moveit_msgs::RobotTrajectory& t)
override;
76 class ThreadedController :
public BaseFakeController
82 bool sendTrajectory(
const moveit_msgs::RobotTrajectory& t)
override;
110 void execTrajectory(
const moveit_msgs::RobotTrajectory& t)
override;
120 void execTrajectory(
const moveit_msgs::RobotTrajectory& t)
override;
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
bool cancelExecution() override
LastPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
std::vector< std::string > joints_
~ViaPointController() override
~LastPointController() override
virtual void execTrajectory(const moveit_msgs::RobotTrajectory &t)=0
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
bool waitForExecution(const ros::Duration &) override
~InterpolatingController() override
BaseFakeController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
MOVEIT_CLASS_FORWARD(BaseFakeController)
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() override
virtual void cancelTrajectory()
ViaPointController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
~ThreadedController() override
bool sendTrajectory(const moveit_msgs::RobotTrajectory &t) override
moveit_controller_manager::ExecutionStatus status_
const ros::Publisher & pub_
void getJoints(std::vector< std::string > &joints) const
bool cancelExecution() override
InterpolatingController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
ThreadedController(const std::string &name, const std::vector< std::string > &joints, const ros::Publisher &pub)
void execTrajectory(const moveit_msgs::RobotTrajectory &t) override
bool waitForExecution(const ros::Duration &) override