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 
42 
43  // In this controller interfaces are optional, so initRequest did not check interface existence
44  // The position interface is OPTIONAL
45  // The effort interface is REQUIRED
46  PosIface* pos_iface = robot_hw->get<PosIface>();
47  EffIface* eff_iface = robot_hw->get<EffIface>();
48 
49  // populate command handles (claimed resources)
50  if (pos_iface)
51  {
52  for (const auto& pos_joint : pos_joints)
53  {
54  pos_cmd_.push_back(pos_iface->getHandle(pos_joint));
55  }
56  }
57  else
58  {
59  ROS_WARN("Optional interface not found: 'hardware_interface::PositionJointInterface'");
60  }
61 
62  if (eff_iface)
63  {
64  for (const auto& eff_joint : eff_joints)
65  {
66  eff_cmd_.push_back(eff_iface->getHandle(eff_joint));
67  }
68  }
69  else
70  {
71  ROS_ERROR("Required interface not found: 'hardware_interface::EffortJointInterface'");
72  return false;
73  }
74 
75  return true;
76 }
77 
79 {
80  ROS_INFO("Starting PosEffOptController");
81 }
82 
83 void PosEffOptController::update(const ros::Time& /*time*/, const ros::Duration& /*period*/)
84 {}
85 
87 {
88  ROS_INFO("Stopping PosEffOptController");
89 }
90 
pos_eff_opt_controller.h
controller_manager_tests::PosEffOptController::pos_cmd_
std::vector< hardware_interface::JointHandle > pos_cmd_
Definition: pos_eff_opt_controller.h:54
controller_manager_tests::PosEffOptController::eff_cmd_
std::vector< hardware_interface::JointHandle > eff_cmd_
Definition: pos_eff_opt_controller.h:55
hardware_interface::InterfaceManager::get
T * get()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
hardware_interface::RobotHW
controller_manager_tests::PosEffOptController::starting
void starting(const ros::Time &time) override
Definition: pos_eff_opt_controller.cpp:78
hardware_interface::EffortJointInterface
ROS_WARN
#define ROS_WARN(...)
controller_manager_tests
Definition: effort_test_controller.h:36
controller_manager_tests::PosEffOptController::stopping
void stopping(const ros::Time &time) override
Definition: pos_eff_opt_controller.cpp:86
controller_manager_tests::PosEffOptController
Definition: pos_eff_opt_controller.h:38
controller_manager_tests::PosEffOptController::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: pos_eff_opt_controller.cpp:83
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
hardware_interface::PositionJointInterface
ROS_INFO
#define ROS_INFO(...)
ros::Duration
controller_manager_tests::PosEffOptController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &n) override
Definition: pos_eff_opt_controller.cpp:32
ros::NodeHandle


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:24