pos_eff_opt_controller.cpp
Go to the documentation of this file.
1 // Copyright (C) 2015, PAL Robotics S.L.
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 names of PAL Robotics S.L. 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 
29 
30 using namespace controller_manager_tests;
31 
33 {
34  std::vector<std::string> pos_joints;
35  if (!n.getParam("position_joints", pos_joints)) {return false;}
36 
37  std::vector<std::string> eff_joints;
38  if (!n.getParam("effort_joints", eff_joints)) {return false;}
39 
40  typedef std::vector<std::string>::const_iterator NamesIterator;
43 
44  // In this controller interfaces are optional, so initRequest did not check interface existence
45  // The position interface is OPTIONAL
46  // The effort interface is REQUIRED
47  PosIface* pos_iface = robot_hw->get<PosIface>();
48  EffIface* eff_iface = robot_hw->get<EffIface>();
49 
50  // populate command handles (claimed resources)
51  if (pos_iface)
52  {
53  for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++)
54  {
55  pos_cmd_.push_back(pos_iface->getHandle(*it));
56  }
57  }
58  else
59  {
60  ROS_WARN("Optional interface not found: 'hardware_interface::PositionJointInterface'");
61  }
62 
63  if (eff_iface)
64  {
65  for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++)
66  {
67  eff_cmd_.push_back(eff_iface->getHandle(*it));
68  }
69  }
70  else
71  {
72  ROS_ERROR("Required interface not found: 'hardware_interface::EffortJointInterface'");
73  return false;
74  }
75 
76  return true;
77 }
78 
80 {
81  ROS_INFO("Starting PosEffOptController");
82 }
83 
84 void PosEffOptController::update(const ros::Time& /*time*/, const ros::Duration& /*period*/)
85 {}
86 
88 {
89  ROS_INFO("Stopping PosEffOptController");
90 }
91 
#define ROS_WARN(...)
std::vector< hardware_interface::JointHandle > eff_cmd_
#define ROS_INFO(...)
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n)
std::vector< hardware_interface::JointHandle > pos_cmd_
void update(const ros::Time &time, const ros::Duration &period)
bool getParam(const std::string &key, std::string &s) const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:10