combined_robot_hw.cpp
Go to the documentation of this file.
1 // Copyright (C) 2015, Shadow Robot Company Ltd.
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 Shadow Robot Company Ltd. 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 #include <algorithm>
30 
31 namespace combined_robot_hw
32 {
34  {
35  root_nh_ = root_nh;
36  robot_hw_nh_ = robot_hw_nh;
37 
38  std::vector<std::string> robots;
39  std::string param_name = "robot_hardware";
40  if (!robot_hw_nh.getParam(param_name, robots))
41  {
42  ROS_ERROR_STREAM("Could not find '" << param_name << "' parameter (namespace: " << robot_hw_nh.getNamespace() << ").");
43  return false;
44  }
45 
46  for (const auto& robot : robots)
47  {
48  if (!loadRobotHW(robot))
49  {
50  return false;
51  }
52  }
53  return true;
54  }
55 
56  bool CombinedRobotHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
57  const std::list<hardware_interface::ControllerInfo>& stop_list)
58  {
59  // Call the prepareSwitch method of the single RobotHW objects.
60  for (const auto& robot_hw : robot_hw_list_)
61  {
62  std::list<hardware_interface::ControllerInfo> filtered_start_list;
63  std::list<hardware_interface::ControllerInfo> filtered_stop_list;
64 
65  // Generate a filtered version of start_list and stop_list for each RobotHW before calling prepareSwitch
66  filterControllerList(start_list, filtered_start_list, robot_hw);
67  filterControllerList(stop_list, filtered_stop_list, robot_hw);
68 
69  if (!robot_hw->prepareSwitch(filtered_start_list, filtered_stop_list))
70  return false;
71  }
72  return true;
73  }
74 
75  void CombinedRobotHW::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
76  const std::list<hardware_interface::ControllerInfo>& stop_list)
77  {
78  // Call the doSwitch method of the single RobotHW objects.
79  for (const auto& robot_hw : robot_hw_list_)
80  {
81  std::list<hardware_interface::ControllerInfo> filtered_start_list;
82  std::list<hardware_interface::ControllerInfo> filtered_stop_list;
83 
84  // Generate a filtered version of start_list and stop_list for each RobotHW before calling doSwitch
85  filterControllerList(start_list, filtered_start_list, robot_hw);
86  filterControllerList(stop_list, filtered_stop_list, robot_hw);
87 
88  robot_hw->doSwitch(filtered_start_list, filtered_stop_list);
89  }
90  }
91 
92  bool CombinedRobotHW::loadRobotHW(const std::string& name)
93  {
94  ROS_DEBUG("Will load robot HW '%s'", name.c_str());
95 
96  ros::NodeHandle c_nh;
97  // Constructs the robot HW
98  try
99  {
100  c_nh = ros::NodeHandle(robot_hw_nh_, name);
101  }
102  catch(std::exception &e)
103  {
104  ROS_ERROR("Exception thrown while constructing nodehandle for robot HW with name '%s':\n%s", name.c_str(), e.what());
105  return false;
106  }
107  catch(...)
108  {
109  ROS_ERROR("Exception thrown while constructing nodehandle for robot HW with name '%s'", name.c_str());
110  return false;
111  }
112 
114  std::string type;
115  if (c_nh.getParam("type", type))
116  {
117  ROS_DEBUG("Constructing robot HW '%s' of type '%s'", name.c_str(), type.c_str());
118  try
119  {
120  for (const auto& cur_type : robot_hw_loader_.getDeclaredClasses())
121  {
122  if (type == cur_type)
123  {
124  robot_hw = robot_hw_loader_.createUniqueInstance(type);
125  }
126  }
127  }
128  catch (const std::runtime_error &ex)
129  {
130  ROS_ERROR("Could not load class %s: %s", type.c_str(), ex.what());
131  }
132  }
133  else
134  {
135  ROS_ERROR("Could not load robot HW '%s' because the type was not specified. Did you load the robot HW configuration on the parameter server (namespace: '%s')?", name.c_str(), c_nh.getNamespace().c_str());
136  return false;
137  }
138 
139  // checks if robot HW was constructed
140  if (!robot_hw)
141  {
142  ROS_ERROR("Could not load robot HW '%s' because robot HW type '%s' does not exist.", name.c_str(), type.c_str());
143  return false;
144  }
145 
146  // Initializes the robot HW
147  ROS_DEBUG("Initializing robot HW '%s'", name.c_str());
148  bool initialized;
149  try
150  {
151  initialized = robot_hw->init(root_nh_, c_nh);
152  }
153  catch(std::exception &e)
154  {
155  ROS_ERROR("Exception thrown while initializing robot HW %s.\n%s", name.c_str(), e.what());
156  initialized = false;
157  }
158  catch(...)
159  {
160  ROS_ERROR("Exception thrown while initializing robot HW %s", name.c_str());
161  initialized = false;
162  }
163 
164  if (!initialized)
165  {
166  ROS_ERROR("Initializing robot HW '%s' failed", name.c_str());
167  return false;
168  }
169  ROS_DEBUG("Initialized robot HW '%s' successful", name.c_str());
170 
171  robot_hw_list_.push_back(robot_hw);
172 
173  this->registerInterfaceManager(robot_hw.get());
174 
175  ROS_DEBUG("Successfully load robot HW '%s'", name.c_str());
176  return true;
177  }
178 
179  void CombinedRobotHW::read(const ros::Time& time, const ros::Duration& period)
180  {
181  // Call the read method of the single RobotHW objects.
182  for (const auto& robot_hw : robot_hw_list_)
183  {
184  robot_hw->read(time, period);
185  }
186  }
187 
188 
189  void CombinedRobotHW::write(const ros::Time& time, const ros::Duration& period)
190  {
191  // Call the write method of the single RobotHW objects.
192  for (const auto& robot_hw : robot_hw_list_)
193  {
194  robot_hw->write(time, period);
195  }
196  }
197 
198  void CombinedRobotHW::filterControllerList(const std::list<hardware_interface::ControllerInfo>& list,
199  std::list<hardware_interface::ControllerInfo>& filtered_list,
201  {
202  filtered_list.clear();
203  for (const auto& controller : list)
204  {
205  hardware_interface::ControllerInfo filtered_controller;
206  filtered_controller.name = controller.name;
207  filtered_controller.type = controller.type;
208 
209  if (controller.claimed_resources.empty())
210  {
211  filtered_list.push_back(filtered_controller);
212  continue;
213  }
214  for (const auto& claimed_resource : controller.claimed_resources)
215  {
216  hardware_interface::InterfaceResources filtered_iface_resources;
217  filtered_iface_resources.hardware_interface = claimed_resource.hardware_interface;
218  std::vector<std::string> r_hw_ifaces = robot_hw->getNames();
219 
220  auto const if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), filtered_iface_resources.hardware_interface);
221  if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered in r_hw, so we filter it out
222  {
223  continue;
224  }
225 
226  std::vector<std::string> r_hw_iface_resources = robot_hw->getInterfaceResources(filtered_iface_resources.hardware_interface);
227  std::set<std::string> filtered_resources;
228  for (const auto& resource : claimed_resource.resources)
229  {
230  std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
231  if (res_name != r_hw_iface_resources.end())
232  {
233  filtered_resources.insert(resource);
234  }
235  }
236  if (!filtered_resources.empty())
237  {
238  filtered_iface_resources.resources = filtered_resources;
239  filtered_controller.claimed_resources.push_back(filtered_iface_resources);
240  }
241  }
242  if (!filtered_controller.claimed_resources.empty())
243  {
244  filtered_list.push_back(filtered_controller);
245  }
246  }
247  }
248 }
combined_robot_hw::CombinedRobotHW::init
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
The init function is called to initialize the RobotHW from a non-realtime thread.
Definition: combined_robot_hw.cpp:33
combined_robot_hw::CombinedRobotHW::robot_hw_loader_
pluginlib::ClassLoader< hardware_interface::RobotHW > robot_hw_loader_
Definition: combined_robot_hw.h:103
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
hardware_interface::InterfaceResources::hardware_interface
std::string hardware_interface
combined_robot_hw::CombinedRobotHW::doSwitch
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
Definition: combined_robot_hw.cpp:75
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
combined_robot_hw.h
combined_robot_hw
Definition: combined_robot_hw.h:42
hardware_interface::ControllerInfo::type
std::string type
hardware_interface::InterfaceManager::registerInterfaceManager
void registerInterfaceManager(InterfaceManager *iface_man)
combined_robot_hw::CombinedRobotHW::robot_hw_list_
std::vector< hardware_interface::RobotHWSharedPtr > robot_hw_list_
Definition: combined_robot_hw.h:104
combined_robot_hw::CombinedRobotHW::prepareSwitch
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
Definition: combined_robot_hw.cpp:56
combined_robot_hw::CombinedRobotHW::robot_hw_nh_
ros::NodeHandle robot_hw_nh_
Definition: combined_robot_hw.h:102
ROS_DEBUG
#define ROS_DEBUG(...)
combined_robot_hw::CombinedRobotHW::write
void write(const ros::Time &time, const ros::Duration &period) override
Definition: combined_robot_hw.cpp:189
combined_robot_hw::CombinedRobotHW::root_nh_
ros::NodeHandle root_nh_
Definition: combined_robot_hw.h:101
hardware_interface::ControllerInfo
hardware_interface::ControllerInfo::claimed_resources
std::vector< InterfaceResources > claimed_resources
combined_robot_hw::CombinedRobotHW::read
void read(const ros::Time &time, const ros::Duration &period) override
Definition: combined_robot_hw.cpp:179
ros::Time
combined_robot_hw::CombinedRobotHW::filterControllerList
void filterControllerList(const std::list< hardware_interface::ControllerInfo > &list, std::list< hardware_interface::ControllerInfo > &filtered_list, hardware_interface::RobotHWSharedPtr robot_hw)
Filters the start and stop lists so that they only contain the controllers and resources that corresp...
Definition: combined_robot_hw.cpp:198
ROS_ERROR
#define ROS_ERROR(...)
hardware_interface::ControllerInfo::name
std::string name
hardware_interface::RobotHWSharedPtr
std::shared_ptr< RobotHW > RobotHWSharedPtr
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
hardware_interface::InterfaceResources
ros::Duration
combined_robot_hw::CombinedRobotHW::loadRobotHW
virtual bool loadRobotHW(const std::string &name)
Definition: combined_robot_hw.cpp:92
hardware_interface::InterfaceResources::resources
std::set< std::string > resources
ros::NodeHandle
pluginlib::ClassLoader::getDeclaredClasses
std::vector< std::string > getDeclaredClasses()


combined_robot_hw
Author(s): Toni Oliver
autogenerated on Tue Oct 15 2024 02:08:20