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


forward_command_controller
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Feb 3 2023 03:19:07