my_robot_hw_2.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 
29 #include <algorithm>
31 
33 {
34 
35 bool MyRobotHW2::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &robot_hw_nh)
36 {
37  using namespace hardware_interface;
38 
39  std::vector<std::string> joints;
40  if (!robot_hw_nh.getParam("joints", joints)) {return false;}
41 
42  // Initialize raw data
43  size_t nb_joints = joints.size();
44  joint_position_.resize(nb_joints);
45  joint_velocity_.resize(nb_joints);
46  joint_effort_.resize(nb_joints);
47  joint_effort_command_.resize(nb_joints);
48  joint_velocity_command_.resize(nb_joints);
49  joint_name_.resize(nb_joints);
50 
51  for (size_t i = 0; i < nb_joints; i++)
52  {
53  joint_name_[i] = joints[i];
54  joint_position_[i] = 1.0;
55  joint_velocity_[i] = 0.0;
56  joint_effort_[i] = 0.1;
57  joint_effort_command_[i] = 0.0;
58  joint_velocity_command_[i] = 0.0;
59  // Populate hardware interfaces
63  }
64 
68 
69  return true;
70 }
71 
72 
73 void MyRobotHW2::read(const ros::Time& /*time*/, const ros::Duration& /*period*/)
74 {
75 
76 }
77 
78 void MyRobotHW2::write(const ros::Time& /*time*/, const ros::Duration& /*period*/)
79 {
80 }
81 
82 bool MyRobotHW2::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
83  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/)
84 {
85  for (const auto& controller : start_list)
86  {
87  if (controller.name == "ctrl_without_my_robot_hw_2_resources")
88  {
89  ROS_ERROR_STREAM("Controller should have been filtered out: " << controller.name);
90  return false;
91  }
92 
93  if (controller.name == "ctrl_without_my_robot_hw_2_resources_in_one_of_two_ifaces")
94  {
95  if (controller.claimed_resources.size() > 1)
96  {
97  ROS_ERROR_STREAM("One of the interfaces should have been filtered out");
98  return false;
99  }
100  }
101 
102  if (controller.claimed_resources.empty())
103  {
104  continue;
105  }
106  for (const auto& res_it : controller.claimed_resources)
107  {
108  std::vector<std::string> r_hw_ifaces = this->getNames();
109 
110  std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface);
111  if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW
112  {
113  ROS_ERROR_STREAM("Bad interface: " << res_it.hardware_interface);
114  return false;
115  }
116 
117  std::vector<std::string> r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface);
118  for (const auto& resource : res_it.resources)
119  {
120  std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
121  if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW
122  {
123  ROS_ERROR_STREAM("Bad resource: " << resource);
124  return false;
125  }
126  }
127  }
128  }
129  return true;
130 }
131 
132 void MyRobotHW2::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
133  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/)
134 {
135  for (const auto& controller : start_list)
136  {
137  if (controller.name == "ctrl_without_my_robot_hw_2_resources")
138  {
139  throw hardware_interface::HardwareInterfaceException("Controller " + controller.name + " should have been filtered out");
140  }
141 
142  if (controller.name == "ctrl_without_my_robot_hw_2_resources_in_one_of_two_ifaces")
143  {
144  if (controller.claimed_resources.size() > 1)
145  {
146  throw hardware_interface::HardwareInterfaceException("One of the interfaces should have been filtered out");
147  }
148  }
149 
150  if (controller.claimed_resources.empty())
151  {
152  continue;
153  }
154  for (const auto& claimed_resource : controller.claimed_resources)
155  {
156  std::vector<std::string> r_hw_ifaces = this->getNames();
157 
158  std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface);
159  if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW
160  {
161  throw hardware_interface::HardwareInterfaceException("Hardware_interface " + claimed_resource.hardware_interface + " is not registered");
162  }
163 
164  std::vector<std::string> r_hw_iface_resources = this->getInterfaceResources(claimed_resource.hardware_interface);
165  for (const auto& resource : claimed_resource.resources)
166  {
167  std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
168  if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW
169  {
170  throw hardware_interface::HardwareInterfaceException("Resource " + resource + " is not registered");
171  }
172  }
173  }
174  }
175 }
176 
177 }
178 
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
hardware_interface::VelocityJointInterface vj_interface_
Definition: my_robot_hw_2.h:54
std::vector< double > joint_position_
Definition: my_robot_hw_2.h:58
std::vector< std::string > joint_name_
Definition: my_robot_hw_2.h:61
hardware_interface::EffortJointInterface ej_interface_
Definition: my_robot_hw_2.h:53
void read(const ros::Time &time, const ros::Duration &period) override
std::vector< double > joint_velocity_
Definition: my_robot_hw_2.h:59
std::vector< std::string > getInterfaceResources(std::string iface_type) const
std::vector< double > joint_velocity_command_
Definition: my_robot_hw_2.h:57
bool getParam(const std::string &key, std::string &s) const
hardware_interface::JointStateInterface js_interface_
Definition: my_robot_hw_2.h:52
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
std::vector< std::string > getNames() const
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
std::vector< double > joint_effort_command_
Definition: my_robot_hw_2.h:56
void write(const ros::Time &time, const ros::Duration &period) override
#define ROS_ERROR_STREAM(args)
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_effort_
Definition: my_robot_hw_2.h:60
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)


combined_robot_hw_tests
Author(s): Toni Oliver
autogenerated on Mon Feb 28 2022 23:30:21