robot_hw.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 #pragma once
29 
30 
31 #include <list>
32 #include <map>
33 #include <memory>
34 #include <typeinfo>
39 #include <ros/console.h>
40 #include <ros/node_handle.h>
41 
42 namespace hardware_interface
43 {
44 
78 class RobotHW : public InterfaceManager
79 {
80 public:
81  virtual ~RobotHW() = default;
82 
102  virtual bool init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &/*robot_hw_nh*/) {return true;}
103 
113  virtual bool checkForConflict(const std::list<ControllerInfo>& info) const
114  {
115  // Map from resource name to all controllers claiming it
116  std::map<std::string, std::list<ControllerInfo>> resource_map;
117 
118  // Populate a map of all controllers claiming individual resources.
119  // We do this by iterating over every claimed resource of every hardware interface used by every controller
120  for (const auto& controller_info : info)
121  {
122  for (const auto& claimed_resource : controller_info.claimed_resources)
123  {
124  for (const auto& iface_resource : claimed_resource.resources)
125  {
126  resource_map[iface_resource].push_back(controller_info);
127  }
128  }
129  }
130 
131  // Enforce resource exclusivity policy: No resource can be claimed by more than one controller
132  bool in_conflict = false;
133  for (const auto& resource_name_and_claiming_controllers : resource_map)
134  {
135  if (resource_name_and_claiming_controllers.second.size() > 1)
136  {
137  std::string controller_list;
138  for (const auto& controller : resource_name_and_claiming_controllers.second)
139  controller_list += controller.name + ", ";
140  ROS_WARN("Resource conflict on [%s]. Controllers = [%s]", resource_name_and_claiming_controllers.first.c_str(), controller_list.c_str());
141  in_conflict = true;
142  }
143  }
144 
145  return in_conflict;
146  }
157  virtual bool prepareSwitch(const std::list<ControllerInfo>& /*start_list*/,
158  const std::list<ControllerInfo>& /*stop_list*/) { return true; }
159 
164  virtual void doSwitch(const std::list<ControllerInfo>& /*start_list*/,
165  const std::list<ControllerInfo>& /*stop_list*/) {}
166 
167  enum class SwitchState
168  {
169  DONE,
170  ONGOING,
171  ERROR
172  };
173 
175  virtual SwitchState switchResult() const
176  {
177  return SwitchState::DONE;
178  }
179 
181  virtual SwitchState switchResult(const ControllerInfo& /*controller*/) const
182  {
183  return SwitchState::DONE;
184  }
206  virtual void read(const ros::Time& /*time*/, const ros::Duration& /*period*/) {}
207 
224  virtual void write(const ros::Time& /*time*/, const ros::Duration& /*period*/) {}
225 
227 };
228 
229 typedef std::shared_ptr<RobotHW> RobotHWSharedPtr;
230 
231 }
hardware_interface::RobotHW::SwitchState::DONE
@ DONE
hardware_interface::InterfaceManager
Manager for hardware interface registrations.
Definition: interface_manager.h:122
node_handle.h
hardware_interface::RobotHW::read
virtual void read(const ros::Time &, const ros::Duration &)
Read data from the robot hardware.
Definition: robot_hw.h:206
hardware_interface::RobotHW::switchResult
virtual SwitchState switchResult(const ControllerInfo &) const
Return (in realtime) the state of the last doSwitch() for a given controller.
Definition: robot_hw.h:181
hardware_interface::RobotHW::doSwitch
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
Definition: robot_hw.h:164
hardware_interface::RobotHW::checkForConflict
virtual bool checkForConflict(const std::list< ControllerInfo > &info) const
Definition: robot_hw.h:113
hardware_interface::RobotHW::init
virtual bool init(ros::NodeHandle &, ros::NodeHandle &)
The init function is called to initialize the RobotHW from a non-realtime thread.
Definition: robot_hw.h:102
console.h
hardware_interface
Definition: actuator_command_interface.h:36
hardware_interface::RobotHW
Robot Hardware Interface and Resource Manager.
Definition: robot_hw.h:78
controller_info.h
hardware_interface::RobotHW::prepareSwitch
virtual bool prepareSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
Definition: robot_hw.h:157
hardware_interface::RobotHW::write
virtual void write(const ros::Time &, const ros::Duration &)
Write commands to the robot hardware.
Definition: robot_hw.h:224
ROS_WARN
#define ROS_WARN(...)
hardware_interface::RobotHW::SwitchState::ERROR
@ ERROR
demangle_symbol.h
hardware_interface::ControllerInfo
Controller Information.
Definition: controller_info.h:44
interface_manager.h
hardware_interface.h
ros::Time
hardware_interface::RobotHW::switchResult
virtual SwitchState switchResult() const
Return (in realtime) the state of the last doSwitch().
Definition: robot_hw.h:175
hardware_interface::RobotHW::SwitchState::ONGOING
@ ONGOING
hardware_interface::RobotHWSharedPtr
std::shared_ptr< RobotHW > RobotHWSharedPtr
Definition: robot_hw.h:229
hardware_interface::RobotHW::SwitchState
SwitchState
Definition: robot_hw.h:167
hardware_interface::RobotHW::~RobotHW
virtual ~RobotHW()=default
ros::Duration
ros::NodeHandle


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:07:57