Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <moveit/macros/class_forward.h>
00039 #include <moveit/controller_manager/controller_manager.h>
00040 #include <ros/publisher.h>
00041 #include <ros/rate.h>
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/thread/thread.hpp>
00044
00045 #ifndef MOVEIT_FAKE_CONTROLLERS
00046 #define MOVEIT_FAKE_CONTROLLERS
00047
00048 namespace moveit_fake_controller_manager
00049 {
00050 MOVEIT_CLASS_FORWARD(BaseFakeController);
00051
00052
00053 class BaseFakeController : public moveit_controller_manager::MoveItControllerHandle
00054 {
00055 public:
00056 BaseFakeController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
00057
00058 virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus();
00059 void getJoints(std::vector<std::string>& joints) const;
00060
00061 protected:
00062 std::vector<std::string> joints_;
00063 const ros::Publisher& pub_;
00064 };
00065
00066 class LastPointController : public BaseFakeController
00067 {
00068 public:
00069 LastPointController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
00070 ~LastPointController();
00071
00072 virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& t);
00073 virtual bool cancelExecution();
00074 virtual bool waitForExecution(const ros::Duration&);
00075 };
00076
00077 class ThreadedController : public BaseFakeController
00078 {
00079 public:
00080 ThreadedController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
00081 ~ThreadedController();
00082
00083 virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory& t);
00084 virtual bool cancelExecution();
00085 virtual bool waitForExecution(const ros::Duration&);
00086 virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus();
00087
00088 protected:
00089 bool cancelled()
00090 {
00091 return cancel_;
00092 }
00093
00094 private:
00095 virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t) = 0;
00096 virtual void cancelTrajectory();
00097
00098 private:
00099 boost::thread thread_;
00100 bool cancel_;
00101 moveit_controller_manager::ExecutionStatus status_;
00102 };
00103
00104 class ViaPointController : public ThreadedController
00105 {
00106 public:
00107 ViaPointController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
00108 ~ViaPointController();
00109
00110 protected:
00111 virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t);
00112 };
00113
00114 class InterpolatingController : public ThreadedController
00115 {
00116 public:
00117 InterpolatingController(const std::string& name, const std::vector<std::string>& joints, const ros::Publisher& pub);
00118 ~InterpolatingController();
00119
00120 protected:
00121 virtual void execTrajectory(const moveit_msgs::RobotTrajectory& t);
00122
00123 private:
00124 ros::WallRate rate_;
00125 };
00126 }
00127
00128 #endif