forward_joint_group_command_controller.h
Go to the documentation of this file.
1 
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * Copyright (c) 2012, hiDOF, Inc.
7  * Copyright (c) 2013, PAL Robotics, S.L.
8  * Copyright (c) 2014, Fraunhofer IPA
9  * All rights reserved.
10  *
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions
13  * are met:
14  *
15  * * Redistributions of source code must retain the above copyright
16  * notice, this list of conditions and the following disclaimer.
17  * * Redistributions in binary form must reproduce the above
18  * copyright notice, this list of conditions and the following
19  * disclaimer in the documentation and/or other materials provided
20  * with the distribution.
21  * * Neither the name of the Willow Garage nor the names of its
22  * contributors may be used to endorse or promote products derived
23  * from this software without specific prior written permission.
24  *
25  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
26  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
27  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
28  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
29  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
30  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
31  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
32  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
33  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  *********************************************************************/
38 
39 #ifndef FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
40 #define FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
41 
42 #include <vector>
43 #include <string>
44 
45 #include <ros/node_handle.h>
48 #include <std_msgs/Float64MultiArray.h>
50 
51 
53 {
54 
72 template <class T>
74 {
75 public:
78 
79  bool init(T* hw, ros::NodeHandle &n)
80  {
81  // List of controlled joints
82  std::string param_name = "joints";
83  if(!n.getParam(param_name, joint_names_))
84  {
85  ROS_ERROR_STREAM("Failed to getParam '" << param_name << "' (namespace: " << n.getNamespace() << ").");
86  return false;
87  }
88  n_joints_ = joint_names_.size();
89 
90  if(n_joints_ == 0){
91  ROS_ERROR_STREAM("List of joint names is empty.");
92  return false;
93  }
94  for(unsigned int i=0; i<n_joints_; i++)
95  {
96  try
97  {
98  joints_.push_back(hw->getHandle(joint_names_[i]));
99  }
101  {
102  ROS_ERROR_STREAM("Exception thrown: " << e.what());
103  return false;
104  }
105  }
106 
107  commands_buffer_.writeFromNonRT(std::vector<double>(n_joints_, 0.0));
108 
109  sub_command_ = n.subscribe<std_msgs::Float64MultiArray>("command", 1, &ForwardJointGroupCommandController::commandCB, this);
110  return true;
111  }
112 
113  void starting(const ros::Time& time);
114  void update(const ros::Time& /*time*/, const ros::Duration& /*period*/)
115  {
116  std::vector<double> & commands = *commands_buffer_.readFromRT();
117  for(unsigned int i=0; i<n_joints_; i++)
118  { joints_[i].setCommand(commands[i]); }
119  }
120 
121  std::vector< std::string > joint_names_;
122  std::vector< hardware_interface::JointHandle > joints_;
124  unsigned int n_joints_;
125 
126 private:
128  void commandCB(const std_msgs::Float64MultiArrayConstPtr& msg)
129  {
130  if(msg->data.size()!=n_joints_)
131  {
132  ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!");
133  return;
134  }
135  commands_buffer_.writeFromNonRT(msg->data);
136  }
137 };
138 
139 }
140 
141 #endif
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void writeFromNonRT(const T &data)
const std::string & getNamespace() const
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)


forward_command_controller
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Apr 11 2019 03:08:19