CsSubscriber.h
Go to the documentation of this file.
00001 #ifndef CSSUBSCRIBER
00002 #define CSSUBSCRIBER 1
00003 #include "Runable.h"
00004 #include "ros/ros.h"
00005 #include <ros/callback_queue.h>
00006 #include <ros/transport_hints.h>
00007 namespace RosCs {
00008         template<class M>
00009         class CsSubscriber : Runable {
00010                 public:
00011                         
00012                         CsSubscriber(void (*cshandle)(char*),char* (*translator)(const boost::shared_ptr<M const > &)) {
00013                                 this->cscallback=cshandle;
00014                                 this->translator=translator;
00015                                 this->running = true;
00016                         }
00017                         void HandleMessage(const boost::shared_ptr<M const >& message) {
00018                                 char* p = translator(message);
00019                                 cscallback(p);
00020                                 delete[] p;
00021                         }
00022                         void Subscribe(ros::NodeHandle* orignh, char* topic, uint32_t queueSize) {
00023                                 nh = ros::NodeHandle(*orignh);
00024                                 nh.setCallbackQueue(&queue);                            
00025                                 sub = nh.subscribe<M,CsSubscriber<M> >(topic, queueSize,&CsSubscriber<M>::HandleMessage,this,ros::TransportHints().unreliable().reliable().tcpNoDelay());
00026 
00027                         }
00028                         void Listen() {
00029                                 while(nh.ok() && this->running) {
00030                                         queue.callAvailable(ros::WallDuration(1));
00031                                 }
00032                                 sub.shutdown();
00033                                 nh.setCallbackQueue(NULL);                              
00034                         }
00035                         /*void Shutdown() {
00036                                 running = false;                                
00037                         }*/
00038                         void SubscribeAndListen(ros::NodeHandle* orignh, char* topic, uint32_t queueSize) {
00039                                 Subscribe(orignh,topic,queueSize);
00040                                 Listen();
00041                         }
00042                         /*void SubscribeAndListen(ros::NodeHandle* orignh, char* topic, uint32_t queueSize) {
00043                                 nh = ros::NodeHandle(*orignh);
00044                                 //ros::CallbackQueue queue;
00045                                 nh.setCallbackQueue(&queue);                            
00046                                 //sub = nh.subscribe<M,CsSubscriber<M> >(topic, queueSize,&CsSubscriber<M>::HandleMessage,this);
00047                                 sub = nh.subscribe<M,CsSubscriber<M> >(topic, queueSize,&CsSubscriber<M>::HandleMessage,this,ros::TransportHints().udp());
00048                                 //,ros::TransportHints().unreliable());
00049                                 
00050                                 
00051                                 while(this->running) {
00052                                         queue.callAvailable(ros::WallDuration(1));//6000));
00053                                 }
00054                                 //queue.callAvailable(ros::WallDuration(30));//6000));
00055                                 
00056                                 
00057                         }*/
00058                         ~CsSubscriber() {
00059                                 //std::cout << "destructor"<<std::endl;
00060                                 running = false;                                
00061                                 sub.shutdown(); 
00062                                 nh.shutdown();                  
00063                                 
00064                         }
00065                         
00066                 protected:
00067                         void (*cscallback)(char*);
00068                         char* (*translator)(const boost::shared_ptr<M const > &);
00069                         ros::Subscriber sub;
00070                         //bool running;
00071                         ros::NodeHandle nh;
00072                         ros::CallbackQueue queue;
00073                 
00074                                         
00075         };
00076         
00077         
00078 };
00079 #endif


roscs
Author(s): hendrik
autogenerated on Sat Dec 28 2013 16:51:21