controller_base.h
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF INC.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 /*
29  * Author: Wim Meeussen
30  */
31 
32 
33 #ifndef CONTROLLER_INTERFACE_CONTROLLER_BASE_H
34 #define CONTROLLER_INTERFACE_CONTROLLER_BASE_H
35 
36 #include <ros/node_handle.h>
38 #include <boost/shared_ptr.hpp>
39 
40 namespace controller_interface
41 {
42 
50 {
51 public:
53  virtual ~ControllerBase(){}
54 
63  virtual void starting(const ros::Time& /*time*/) {};
64 
70  virtual void update(const ros::Time& time, const ros::Duration& period) = 0;
71 
77  virtual void stopping(const ros::Time& /*time*/) {};
78 
82  bool isRunning()
83  {
84  return (state_ == RUNNING);
85  }
86 
88  void updateRequest(const ros::Time& time, const ros::Duration& period)
89  {
90  if (state_ == RUNNING)
91  update(time, period);
92  }
93 
95  bool startRequest(const ros::Time& time)
96  {
97  // start succeeds even if the controller was already started
98  if (state_ == RUNNING || state_ == INITIALIZED){
99  starting(time);
100  state_ = RUNNING;
101  return true;
102  }
103  else
104  return false;
105  }
106 
108  bool stopRequest(const ros::Time& time)
109  {
110  // stop succeeds even if the controller was already stopped
111  if (state_ == RUNNING || state_ == INITIALIZED){
112  stopping(time);
114  return true;
115  }
116  else
117  return false;
118  }
119 
120  /*\}*/
121 
125  typedef std::vector<hardware_interface::InterfaceResources> ClaimedResources;
126 
143  virtual bool initRequest(hardware_interface::RobotHW* robot_hw,
144  ros::NodeHandle& root_nh,
145  ros::NodeHandle& controller_nh,
146  ClaimedResources& claimed_resources) = 0;
147 
148  /*\}*/
149 
152 
153 
154 private:
155  ControllerBase(const ControllerBase &c);
157 
158 };
159 
161 
162 }
163 
164 
165 #endif
bool isRunning()
Check if the controller is running.
std::vector< hardware_interface::InterfaceResources > ClaimedResources
virtual void stopping(const ros::Time &)
This is called from within the realtime thread just after the last update call before the controller ...
virtual void update(const ros::Time &time, const ros::Duration &period)=0
This is called periodically by the realtime thread when the controller is running.
Abstract Controller Interface.
void updateRequest(const ros::Time &time, const ros::Duration &period)
Calls update only if this controller is running.
boost::shared_ptr< ControllerBase > ControllerBaseSharedPtr
bool startRequest(const ros::Time &time)
Calls starting only if this controller is initialized or already running.
virtual bool initRequest(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)=0
Request that the controller be initialized.
bool stopRequest(const ros::Time &time)
Calls stopping only if this controller is initialized or already running.
enum controller_interface::ControllerBase::@0 state_
The current execution state of the controller.
ControllerBase & operator=(const ControllerBase &c)
virtual void starting(const ros::Time &)
This is called from within the realtime thread just before the first call to update.


controller_interface
Author(s): Wim Meeussen
autogenerated on Mon Apr 20 2020 03:52:08