controller_base.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 
00033 #ifndef CONTROLLER_INTERFACE_CONTROLLER_BASE_H
00034 #define CONTROLLER_INTERFACE_CONTROLLER_BASE_H
00035 
00036 #include <ros/node_handle.h>
00037 #include <hardware_interface/robot_hw.h>
00038 #include <boost/shared_ptr.hpp>
00039 
00040 
00041 namespace controller_interface
00042 {
00043 
00050 class ControllerBase
00051 {
00052 public:
00053   ControllerBase(): state_(CONSTRUCTED){}
00054   virtual ~ControllerBase(){}
00055 
00064   virtual void starting(const ros::Time& /*time*/) {};
00065 
00071   virtual void update(const ros::Time& time, const ros::Duration& period) = 0;
00072 
00078   virtual void stopping(const ros::Time& /*time*/) {};
00079 
00083   bool isRunning()
00084   {
00085     return (state_ == RUNNING);
00086   }
00087 
00089   void updateRequest(const ros::Time& time, const ros::Duration& period)
00090   {
00091     if (state_ == RUNNING)
00092       update(time, period);
00093   }
00094 
00096   bool startRequest(const ros::Time& time)
00097   {
00098     // start succeeds even if the controller was already started
00099     if (state_ == RUNNING || state_ == INITIALIZED){
00100       starting(time);
00101       state_ = RUNNING;
00102       return true;
00103     }
00104     else
00105       return false;
00106   }
00107 
00109   bool stopRequest(const ros::Time& time)
00110   {
00111     // stop succeeds even if the controller was already stopped
00112     if (state_ == RUNNING || state_ == INITIALIZED){
00113       stopping(time);
00114       state_ = INITIALIZED;
00115       return true;
00116     }
00117     else
00118       return false;
00119   }
00120 
00121   /*\}*/
00122 
00126 
00127   virtual std::string getHardwareInterfaceType() const = 0;
00128 
00144   virtual bool initRequest(hardware_interface::RobotHW* hw, ros::NodeHandle& root_nh, ros::NodeHandle &controller_nh,
00145                            std::set<std::string>& claimed_resources) = 0;
00146 
00147   /*\}*/
00148 
00150   enum {CONSTRUCTED, INITIALIZED, RUNNING} state_;
00151 
00152 
00153 private:
00154   ControllerBase(const ControllerBase &c);
00155   ControllerBase& operator =(const ControllerBase &c);
00156 
00157 };
00158 
00159 typedef boost::shared_ptr<ControllerBase> ControllerBaseSharedPtr;
00160 
00161 }
00162 
00163 
00164 #endif


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