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
00027
00028
00029
00030
00031
00032 #ifndef CONTROLLER_INTERFACE_CONTROLLER_H
00033 #define CONTROLLER_INTERFACE_CONTROLLER_H
00034
00035 #include <controller_interface/controller_base.h>
00036 #include <hardware_interface/internal/demangle_symbol.h>
00037 #include <hardware_interface/robot_hw.h>
00038 #include <hardware_interface/hardware_interface.h>
00039 #include <ros/ros.h>
00040
00041
00042 namespace controller_interface
00043 {
00044
00051 template <class T>
00052 class Controller: public ControllerBase
00053 {
00054 public:
00055 Controller() {state_ = CONSTRUCTED;}
00056 virtual ~Controller<T>(){}
00057
00071 virtual bool init(T* , ros::NodeHandle& ) {return true;};
00072
00088 virtual bool init(T* , ros::NodeHandle& , ros::NodeHandle& ) {return true;};
00089
00090
00091 protected:
00098 virtual bool initRequest(hardware_interface::RobotHW* robot_hw,
00099 ros::NodeHandle& root_nh,
00100 ros::NodeHandle& controller_nh,
00101 ClaimedResources& claimed_resources)
00102 {
00103
00104 if (state_ != CONSTRUCTED){
00105 ROS_ERROR("Cannot initialize this controller because it failed to be constructed");
00106 return false;
00107 }
00108
00109
00110 T* hw = robot_hw->get<T>();
00111 if (!hw)
00112 {
00113 ROS_ERROR("This controller requires a hardware interface of type '%s'."
00114 " Make sure this is registered in the hardware_interface::RobotHW class.",
00115 getHardwareInterfaceType().c_str());
00116 return false;
00117 }
00118
00119
00120 hw->clearClaims();
00121 if (!init(hw, controller_nh) || !init(hw, root_nh, controller_nh))
00122 {
00123 ROS_ERROR("Failed to initialize the controller");
00124 return false;
00125 }
00126 hardware_interface::InterfaceResources iface_res(getHardwareInterfaceType(), hw->getClaims());
00127 claimed_resources.assign(1, iface_res);
00128 hw->clearClaims();
00129
00130
00131 state_ = INITIALIZED;
00132 return true;
00133 }
00134
00136 std::string getHardwareInterfaceType() const
00137 {
00138 return hardware_interface::internal::demangledTypeName<T>();
00139 }
00140
00141 private:
00142 Controller<T>(const Controller<T> &c);
00143 Controller<T>& operator =(const Controller<T> &c);
00144
00145 };
00146
00147 }
00148
00149 #endif