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