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


combined_robot_hw_tests
Author(s): Toni Oliver
autogenerated on Fri Jun 7 2019 22:00:11