controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2015, Fetch Robotics Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Fetch Robotics Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL FETCH ROBOTICS INC. BE LIABLE FOR ANY
21  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
26  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 // Author: Michael Ferguson
30 
31 #ifndef ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H
32 #define ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H
33 
34 #include <string>
35 #include <vector>
36 #include <boost/shared_ptr.hpp>
37 #include <ros/ros.h>
39 
55 {
56 
57 // Forward define
58 class ControllerManager;
59 
66 class Controller : public Handle
67 {
68 public:
73  {
74  }
75 
77  virtual ~Controller()
78  {
79  }
80 
88  virtual int init(ros::NodeHandle& nh, ControllerManager* manager)
89  {
90  name_ = nh.getNamespace();
91  // remove leading slash
92  if (name_.at(0) == '/')
93  name_.erase(0, 1);
94  return 0;
95  }
96 
102  virtual bool start() = 0;
103 
111  virtual bool stop(bool force) = 0;
112 
119  virtual bool reset() = 0;
120 
126  virtual void update(const ros::Time& time, const ros::Duration& dt) = 0;
127 
129  std::string getName()
130  {
131  return name_;
132  }
133 
135  virtual std::string getType()
136  {
137  return "UnknownType";
138  }
139 
141  virtual std::vector<std::string> getCommandedNames() = 0;
142 
144  virtual std::vector<std::string> getClaimedNames() = 0;
145 
146 private:
147  std::string name_;
148 };
149 
150 // Some typedefs
152 
153 } // namespace robot_controllers
154 
155 #endif // ROBOT_CONTROLLERS_INTERFACE_CONTROLLER_H
Controller()
Default constructor, does almost nothing, all setup is done in init().
Definition: controller.h:72
virtual bool start()=0
Attempt to start the controller. This should be called only by the ControllerManager instance...
virtual bool reset()=0
Cleanly reset the controller to it&#39;s initial state. Some controllers may choose to stop themselves...
virtual std::vector< std::string > getCommandedNames()=0
Get the names of joints/controllers which this controller commands.
virtual void update(const ros::Time &time, const ros::Duration &dt)=0
This is the update loop for the controller.
Base class for a handle.
Definition: handle.h:43
boost::shared_ptr< Controller > ControllerPtr
Definition: controller.h:151
Base class for a controller manager.
const std::string & getNamespace() const
virtual std::string getType()
Get the type of this controller.
Definition: controller.h:135
virtual std::vector< std::string > getClaimedNames()=0
Get the names of joints/controllers which this controller exclusively claims.
Base class for a controller. Is derived from a Handle, so that controllers can be passed from Control...
Definition: controller.h:66
virtual bool stop(bool force)=0
Attempt to stop the controller. This should be called only by the ControllerManager instance...
virtual int init(ros::NodeHandle &nh, ControllerManager *manager)
Initialize the controller and any required data structures.
Definition: controller.h:88
std::string getName()
Get the name of this controller.
Definition: controller.h:129
virtual ~Controller()
Ensure proper cleanup with virtual destructor.
Definition: controller.h:77


robot_controllers_interface
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:36