forward_joint_group_command_controller.h
Go to the documentation of this file.
00001 
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  Copyright (c) 2012, hiDOF, Inc.
00007  *  Copyright (c) 2013, PAL Robotics, S.L.
00008  *  Copyright (c) 2014, Fraunhofer IPA
00009  *  All rights reserved.
00010  *
00011  *  Redistribution and use in source and binary forms, with or without
00012  *  modification, are permitted provided that the following conditions
00013  *  are met:
00014  *
00015  *   * Redistributions of source code must retain the above copyright
00016  *     notice, this list of conditions and the following disclaimer.
00017  *   * Redistributions in binary form must reproduce the above
00018  *     copyright notice, this list of conditions and the following
00019  *     disclaimer in the documentation and/or other materials provided
00020  *     with the distribution.
00021  *   * Neither the name of the Willow Garage nor the names of its
00022  *     contributors may be used to endorse or promote products derived
00023  *     from this software without specific prior written permission.
00024  *
00025  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036  *  POSSIBILITY OF SUCH DAMAGE.
00037  *********************************************************************/
00038 
00039 #ifndef FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
00040 #define FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
00041 
00042 #include <vector>
00043 #include <string>
00044 
00045 #include <ros/node_handle.h>
00046 #include <hardware_interface/joint_command_interface.h>
00047 #include <controller_interface/controller.h>
00048 #include <std_msgs/Float64MultiArray.h>
00049 #include <realtime_tools/realtime_buffer.h>
00050 
00051 
00052 namespace forward_command_controller
00053 {
00054 
00072 template <class T>
00073 class ForwardJointGroupCommandController: public controller_interface::Controller<T>
00074 {
00075 public:
00076   ForwardJointGroupCommandController() {}
00077   ~ForwardJointGroupCommandController() {sub_command_.shutdown();}
00078 
00079   bool init(T* hw, ros::NodeHandle &n)
00080   {
00081     // List of controlled joints
00082     std::string param_name = "joints";
00083     if(!n.getParam(param_name, joint_names_))
00084     {
00085       ROS_ERROR_STREAM("Failed to getParam '" << param_name << "' (namespace: " << n.getNamespace() << ").");
00086       return false;
00087     }
00088     n_joints_ = joint_names_.size();
00089 
00090     if(n_joints_ == 0){
00091       ROS_ERROR_STREAM("List of joint names is empty.");
00092       return false;
00093     }
00094     for(unsigned int i=0; i<n_joints_; i++)
00095     {
00096       try
00097       {
00098         joints_.push_back(hw->getHandle(joint_names_[i]));  
00099       }
00100       catch (const hardware_interface::HardwareInterfaceException& e)
00101       {
00102         ROS_ERROR_STREAM("Exception thrown: " << e.what());
00103         return false;
00104       }
00105     }
00106 
00107     commands_buffer_.writeFromNonRT(std::vector<double>(n_joints_, 0.0));
00108 
00109     sub_command_ = n.subscribe<std_msgs::Float64MultiArray>("command", 1, &ForwardJointGroupCommandController::commandCB, this);
00110     return true;
00111   }
00112 
00113   void starting(const ros::Time& time);
00114   void update(const ros::Time& /*time*/, const ros::Duration& /*period*/)
00115   {
00116     std::vector<double> & commands = *commands_buffer_.readFromRT();
00117     for(unsigned int i=0; i<n_joints_; i++)
00118     {  joints_[i].setCommand(commands[i]);  }
00119   }
00120 
00121   std::vector< std::string > joint_names_;
00122   std::vector< hardware_interface::JointHandle > joints_;
00123   realtime_tools::RealtimeBuffer<std::vector<double> > commands_buffer_;
00124   unsigned int n_joints_;
00125 
00126 private:
00127   ros::Subscriber sub_command_;
00128   void commandCB(const std_msgs::Float64MultiArrayConstPtr& msg) 
00129   {
00130     if(msg->data.size()!=n_joints_)
00131     { 
00132       ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!");
00133       return; 
00134     }
00135     commands_buffer_.writeFromNonRT(msg->data);
00136   }
00137 };
00138 
00139 }
00140 
00141 #endif


forward_command_controller
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Jun 6 2019 18:58:53