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


combined_robot_hw_tests
Author(s): Toni Oliver
autogenerated on Mon Apr 20 2020 03:52:11