controller.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 #ifndef CONTROLLER_INTERFACE_CONTROLLER_H
33 #define CONTROLLER_INTERFACE_CONTROLLER_H
34 
39 #include <ros/ros.h>
40 
41 
43 {
44 
51 template <class T>
53 {
54 public:
56  virtual ~Controller<T>(){}
57 
71  virtual bool init(T* /*hw*/, ros::NodeHandle& /*controller_nh*/) {return true;};
72 
88  virtual bool init(T* /*hw*/, ros::NodeHandle& /*root_nh*/, ros::NodeHandle& /*controller_nh*/) {return true;};
89 
90 
91 protected:
98  virtual bool initRequest(hardware_interface::RobotHW* robot_hw,
99  ros::NodeHandle& root_nh,
100  ros::NodeHandle& controller_nh,
101  ClaimedResources& claimed_resources)
102  {
103  // check if construction finished cleanly
104  if (state_ != CONSTRUCTED){
105  ROS_ERROR("Cannot initialize this controller because it failed to be constructed");
106  return false;
107  }
108 
109  // get a pointer to the hardware interface
110  T* hw = robot_hw->get<T>();
111  if (!hw)
112  {
113  ROS_ERROR("This controller requires a hardware interface of type '%s'."
114  " Make sure this is registered in the hardware_interface::RobotHW class.",
115  getHardwareInterfaceType().c_str());
116  return false;
117  }
118 
119  // return which resources are claimed by this controller
120  hw->clearClaims();
121  if (!init(hw, controller_nh) || !init(hw, root_nh, controller_nh))
122  {
123  ROS_ERROR("Failed to initialize the controller");
124  return false;
125  }
127  claimed_resources.assign(1, iface_res);
128  hw->clearClaims();
129 
130  // success
132  return true;
133  }
134 
136  std::string getHardwareInterfaceType() const
137  {
138  return hardware_interface::internal::demangledTypeName<T>();
139  }
140 
141 private:
142  Controller<T>(const Controller<T> &c);
144 
145 };
146 
147 }
148 
149 #endif
virtual bool initRequest(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
Initialize the controller from a RobotHW pointer.
Definition: controller.h:98
virtual bool init(T *, ros::NodeHandle &, ros::NodeHandle &)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
Definition: controller.h:88
std::vector< hardware_interface::InterfaceResources > ClaimedResources
std::string getHardwareInterfaceType() const
Get the name of this controller&#39;s hardware interface type.
Definition: controller.h:136
Abstract Controller Interface.
virtual bool init(T *, ros::NodeHandle &)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
Definition: controller.h:71
Controller with a specific hardware interface
Definition: controller.h:52
enum controller_interface::ControllerBase::@0 state_
The current execution state of the controller.
#define ROS_ERROR(...)
Controller< T > & operator=(const Controller< T > &c)


controller_interface
Author(s): Wim Meeussen
autogenerated on Fri Jun 7 2019 22:00:06