AsyncMerger.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *  Created on: 26.06.2013.
00035  *  Author: Dula Nad
00036  *********************************************************************/
00037 #ifndef ASYNCMERGER_HPP_
00038 #define ASYNCMERGER_HPP_
00039 #include <labust/tools/conversions.hpp>
00040 
00041 #include <auv_msgs/BodyForceReq.h>
00042 #include <auv_msgs/BodyVelocityReq.h>
00043 #include <std_msgs/Float32.h>
00044 #include <ros/ros.h>
00045 
00046 #include <boost/thread/mutex.hpp>
00047 
00048 #include <vector>
00049 #include <string>
00050 #include <map>
00051 
00052 namespace labust
00053 {
00054         namespace control
00055         {
00056                 class AsyncMergerBase
00057                 {
00058                         typedef std::map<std::string,bool> ControllerMap;
00059                 public:
00060                         typedef boost::shared_ptr<AsyncMergerBase> Ptr;
00061                 protected:
00065                         AsyncMergerBase();
00069                         virtual ~AsyncMergerBase(){};
00073                         void copyToVector(const auv_msgs::BodyForceReq::ConstPtr& topic, bool* axis, double* val);
00077                         void copyFromVector(const auv_msgs::BodyForceReq::Ptr& topic, bool* axis, double* val);
00081                         void copyToVector(const auv_msgs::BodyVelocityReq::ConstPtr& topic, bool* axis, double* val);
00085                         void copyFromVector(const auv_msgs::BodyVelocityReq::Ptr& topic, bool* axis, double* val);
00086 
00090                         void handleRequester(const std::string& requester);
00094                         bool allArrived();
00098                         void clearAll();
00102                         void reset_axes();
00106                         void checkArrived(const ros::TimerEvent& event);
00110                         virtual void publishFinal() = 0;
00111 
00115                         ControllerMap controllers;
00119                         ros::Subscriber in;
00123                         ros::Publisher out, loop_time;
00127                         ros::Timer timer;
00131                         ros::Time lastAll;
00132 
00136                         bool outaxis[6];
00140                         double outval[6];
00144                         boost::mutex cnt_mux;
00148                         double Ts;
00149                 };
00150 
00151 
00152                 template <class Topic>
00153                 struct AsyncMerger : public virtual AsyncMergerBase
00154                 {
00155 
00156                 public:
00157                         AsyncMerger(){this->onInit();};
00158 
00159                         void onInit()
00160                         {
00161                                 ros::NodeHandle nh;
00162                                 in = nh.subscribe<Topic>("in", 0, &AsyncMerger::onTopic, this);
00163                                 out = nh.advertise<Topic>("out",1);
00164                         }
00165 
00166                 private:
00170                         void onTopic(const typename Topic::ConstPtr& topic)
00171                         {
00172                                 bool axis[6];
00173                                 double val[6];
00174                                 this->copyToVector(topic,axis,val);
00175 
00176                                 boost::mutex::scoped_lock l(cnt_mux);
00177                                 for(int i=0; i<6; ++i)
00178                                 {
00179                                         if (!axis[i])
00180                                         {
00181 
00182                                                 outaxis[i] = axis[i];
00183                                                 outval[i] = val[i];
00184                                         }
00185                                 }
00186                                 this->handleRequester(topic->goal.requester);
00187                         }
00188 
00192                         void publishFinal()
00193                         {
00194                                 typename Topic::Ptr outTopic(new Topic());
00195                                 outTopic->header.stamp = ros::Time::now();
00196                                 outTopic->goal.requester = "async_merger";
00197 
00198                                 this->copyFromVector(outTopic, outaxis, outval);
00199                                 out.publish(outTopic);
00200                                 std_msgs::Float32 data;
00201                                 data.data = (ros::Time::now() - lastAll).toSec();
00202                                 loop_time.publish(data);
00203                         }
00204 
00205                 };
00206         }
00207 }
00208 /* ASYNCMERGER_HPP_ */
00209 #endif


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42