my_robot_hw_1.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 MyRobotHW1::init(ros::NodeHandle& /*root_nh*/, ros::NodeHandle &/*robot_hw_nh*/)
36 {
37  using namespace hardware_interface;
38 
39  // Initialize raw data
40  joint_position_.resize(3);
41  joint_velocity_.resize(3);
42  joint_effort_.resize(3);
43  joint_effort_command_.resize(3);
44  joint_velocity_command_.resize(3);
45  joint_name_.resize(3);
46 
47  joint_name_[0] = "test_joint1";
48  joint_position_[0] = 1.0;
49  joint_velocity_[0] = 0.0;
50  joint_effort_[0] = 0.1;
51  joint_effort_command_[0] = 3.0;
52  joint_velocity_command_[0] = 0.0;
53 
54  joint_name_[1] = "test_joint2";
55  joint_position_[1] = 1.0;
56  joint_velocity_[1] = 0.0;
57  joint_effort_[1] = 0.1;
58  joint_effort_command_[1] = 0.0;
59  joint_velocity_command_[1] = 0.0;
60 
61  joint_name_[2] = "test_joint3";
62  joint_position_[2] = 1.0;
63  joint_velocity_[2] = 0.0;
64  joint_effort_[2] = 0.1;
65  joint_effort_command_[2] = 0.0;
66  joint_velocity_command_[2] = 0.0;
67 
68  // Populate hardware interfaces
72 
76 
80 
84 
85  return true;
86 }
87 
88 
89 void MyRobotHW1::read(const ros::Time& /*time*/, const ros::Duration& /*period*/)
90 {
91  joint_position_[0] = 2.7;
92 }
93 
94 void MyRobotHW1::write(const ros::Time& /*time*/, const ros::Duration& /*period*/)
95 {
96  // Just to test that write() is called
98 }
99 
100 bool MyRobotHW1::prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
101  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/)
102 {
103  for (const auto& controller : start_list)
104  {
105  if (controller.claimed_resources.empty())
106  {
107  continue;
108  }
109  for (const auto& res_it : controller.claimed_resources)
110  {
111  std::vector<std::string> r_hw_ifaces = this->getNames();
112 
113  std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface);
114  if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW
115  {
116  ROS_ERROR_STREAM("Bad interface: " << res_it.hardware_interface);
117  std::cout << res_it.hardware_interface;
118  return false;
119  }
120 
121  std::vector<std::string> r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface);
122  for (const auto& resource : res_it.resources)
123  {
124  std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
125  if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW
126  {
127  ROS_ERROR_STREAM("Bad resource: " << resource);
128  std::cout << resource;
129  return false;
130  }
131  }
132  }
133  }
134  return true;
135 }
136 
137 void MyRobotHW1::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
138  const std::list<hardware_interface::ControllerInfo>& /*stop_list*/)
139 {
140  for (const auto& controller : start_list)
141  {
142  if (controller.claimed_resources.empty())
143  {
144  continue;
145  }
146  for (const auto& claimed_resource : controller.claimed_resources)
147  {
148  std::vector<std::string> r_hw_ifaces = this->getNames();
149 
150  std::vector<std::string>::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface);
151  if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW
152  {
153  throw hardware_interface::HardwareInterfaceException("Hardware_interface " + claimed_resource.hardware_interface + " is not registered");
154  }
155 
156  std::vector<std::string> r_hw_iface_resources = this->getInterfaceResources(claimed_resource.hardware_interface);
157  for (const auto& resource : claimed_resource.resources)
158  {
159  std::vector<std::string>::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource);
160  if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW
161  {
162  throw hardware_interface::HardwareInterfaceException("Resource " + resource + " is not registered");
163  }
164  }
165  }
166  }
167 }
168 
169 }
170 
hardware_interface::VelocityJointInterface vj_interface_
Definition: my_robot_hw_1.h:54
hardware_interface::JointStateInterface js_interface_
Definition: my_robot_hw_1.h:52
bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_velocity_
Definition: my_robot_hw_1.h:59
std::vector< double > joint_velocity_command_
Definition: my_robot_hw_1.h:57
std::vector< std::string > getInterfaceResources(std::string iface_type) const
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
void write(const ros::Time &time, const ros::Duration &period) override
std::vector< std::string > joint_name_
Definition: my_robot_hw_1.h:61
std::vector< double > joint_effort_command_
Definition: my_robot_hw_1.h:56
void read(const ros::Time &time, const ros::Duration &period) override
std::vector< std::string > getNames() const
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
std::vector< double > joint_effort_
Definition: my_robot_hw_1.h:60
void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list) override
std::vector< double > joint_position_
Definition: my_robot_hw_1.h:58
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::EffortJointInterface ej_interface_
Definition: my_robot_hw_1.h:53


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