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 #pragma once
00035
00043
00044
00045 #include <ros/node_handle.h>
00046 #include <pr2_mechanism_model/robot.h>
00047 #include <pr2_controller_interface/controller_provider.h>
00048 #include <controller_interface/controller.h>
00049
00050 namespace pr2_controller_interface
00051 {
00052
00053 class Controller : public controller_interface::Controller<pr2_mechanism_model::RobotState >
00054 {
00055 public:
00056 enum {BEFORE_ME, AFTER_ME};
00057
00058 Controller(): state_(CONSTRUCTED){}
00059 virtual ~Controller(){}
00060
00061 void starting(const ros::Time& time) { starting(); }
00062 void update (const ros::Time& time, const ros::Duration& period) { update(); }
00063 void stopping(const ros::Time& time) { stopping(); }
00064
00066 virtual void starting() {};
00067
00069 virtual void update(void) = 0;
00070
00072 virtual void stopping() {};
00073
00087 virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) = 0;
00088
00090 template<class ControllerType> bool getController(const std::string& name, int sched, ControllerType*& c)
00091 {
00092 if (contr_prov_ == NULL){
00093 ROS_ERROR("No valid pointer to a controller provider exists");
00094 return false;
00095 }
00096 if (!contr_prov_->getControllerByName(name, c)){
00097 ROS_ERROR("Could not find controller %s", name.c_str());
00098 return false;
00099 }
00100 if (sched == BEFORE_ME) before_list_.push_back(name);
00101 else if (sched == AFTER_ME) after_list_.push_back(name);
00102 else{
00103 ROS_ERROR("No valid scheduling specified. Need BEFORE_ME or AFTER_ME in getController function");
00104 return false;
00105 }
00106 return true;
00107 }
00108
00110 bool isRunning()
00111 {
00112 return (state_ == RUNNING);
00113 }
00114
00115 void updateRequest()
00116 {
00117 if (state_ == RUNNING)
00118 update();
00119 }
00120
00121 bool startRequest()
00122 {
00123
00124 if (state_ == RUNNING || state_ == INITIALIZED){
00125 starting();
00126 state_ = RUNNING;
00127 return true;
00128 }
00129 else
00130 return false;
00131 }
00132
00133
00134 bool stopRequest()
00135 {
00136
00137 if (state_ == RUNNING || state_ == INITIALIZED){
00138 stopping();
00139 state_ = INITIALIZED;
00140 return true;
00141 }
00142 else
00143 return false;
00144 }
00145
00146 bool initRequest(ControllerProvider* cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00147 {
00148 contr_prov_ = cp;
00149
00150 if (state_ != CONSTRUCTED)
00151 return false;
00152 else
00153 {
00154
00155 if (!init(robot, n))
00156 return false;
00157 state_ = INITIALIZED;
00158
00159 return true;
00160 }
00161 }
00162
00163
00164 std::vector<std::string> before_list_, after_list_;
00165
00166 enum {CONSTRUCTED, INITIALIZED, RUNNING} state_;
00167
00168 private:
00169 Controller(const Controller &c);
00170 Controller& operator =(const Controller &c);
00171 ControllerProvider* contr_prov_;
00172
00173 };
00174
00175 }