Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
00209 #endif