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 #pragma once
33 
34 
39 #include <ros/ros.h>
40 
41 
43 {
44 
51 template <class T>
52 class Controller: public virtual ControllerBase
53 {
54 public:
55 
69  virtual bool init(T* /*hw*/, ros::NodeHandle& /*controller_nh*/) {return true;};
70 
86  virtual bool init(T* /*hw*/, ros::NodeHandle& /*root_nh*/, ros::NodeHandle& /*controller_nh*/) {return true;};
87 
88 
89 protected:
97  ros::NodeHandle& root_nh,
98  ros::NodeHandle& controller_nh,
99  ClaimedResources& claimed_resources) override
100  {
101  // check if construction finished cleanly
102  if (state_ != CONSTRUCTED){
103  ROS_ERROR("Cannot initialize this controller because it failed to be constructed");
104  return false;
105  }
106 
107  // get a pointer to the hardware interface
108  T* hw = robot_hw->get<T>();
109  if (!hw)
110  {
111  ROS_ERROR("This controller requires a hardware interface of type '%s'."
112  " Make sure this is registered in the hardware_interface::RobotHW class.",
113  getHardwareInterfaceType().c_str());
114  return false;
115  }
116 
117  // return which resources are claimed by this controller
118  hw->clearClaims();
119  if (!init(hw, controller_nh) || !init(hw, root_nh, controller_nh))
120  {
121  ROS_ERROR("Failed to initialize the controller");
122  return false;
123  }
125  claimed_resources.assign(1, iface_res);
126  hw->clearClaims();
127 
128  // success
130  return true;
131  }
132 
134  std::string getHardwareInterfaceType() const
135  {
136  return hardware_interface::internal::demangledTypeName<T>();
137  }
138 };
139 
140 }
std::string getHardwareInterfaceType() const
Get the name of this controller&#39;s hardware interface type.
Definition: controller.h:134
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:86
bool initRequest(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
Initialize the controller from a RobotHW pointer.
Definition: controller.h:96
std::vector< hardware_interface::InterfaceResources > ClaimedResources
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:69
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_interface
Author(s): Wim Meeussen
autogenerated on Mon Feb 28 2022 23:30:15