controller.h
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2012, hiDOF INC.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of hiDOF, Inc. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00028 /*
00029  * Author: Wim Meeussen
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* /*hw*/, ros::NodeHandle& /*controller_nh*/) {return true;};
00072 
00088   virtual bool init(T* /*hw*/, ros::NodeHandle& /*root_nh*/, ros::NodeHandle& /*controller_nh*/) {return true;};
00089 
00090 
00091 protected:
00098   virtual bool initRequest(hardware_interface::RobotHW* robot_hw,
00099                            ros::NodeHandle& root_nh, ros::NodeHandle &controller_nh,
00100                            std::set<std::string> &claimed_resources)
00101   {
00102     // check if construction finished cleanly
00103     if (state_ != CONSTRUCTED){
00104       ROS_ERROR("Cannot initialize this controller because it failed to be constructed");
00105       return false;
00106     }
00107 
00108     // get a pointer to the hardware interface
00109     T* hw = robot_hw->get<T>();
00110     if (!hw)
00111     {
00112       ROS_ERROR("This controller requires a hardware interface of type '%s'."
00113                 " Make sure this is registered in the hardware_interface::RobotHW class.",
00114                 getHardwareInterfaceType().c_str());
00115       return false;
00116     }
00117 
00118     // return which resources are claimed by this controller
00119     hw->clearClaims();
00120     if (!init(hw, controller_nh) || !init(hw, root_nh, controller_nh))
00121     {
00122       ROS_ERROR("Failed to initialize the controller");
00123       return false;
00124     }
00125     claimed_resources = hw->getClaims();
00126     hw->clearClaims();
00127 
00128     // success
00129     state_ = INITIALIZED;
00130     return true;
00131   }
00132 
00133   virtual std::string getHardwareInterfaceType() const
00134   {
00135     return hardware_interface::internal::demangledTypeName<T>();
00136   }
00137 
00138 private:
00139   Controller<T>(const Controller<T> &c);
00140   Controller<T>& operator =(const Controller<T> &c);
00141 
00142 };
00143 
00144 }
00145 
00146 #endif


controller_interface
Author(s): Wim Meeussen
autogenerated on Sat Jun 8 2019 20:09:22