node_handle.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Willow Garage, Inc.
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 Willow Garage, Inc. nor the names of its
00018  *    contributors may be used to endorse or promote prducts 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 
00035 #ifndef ROS_NODE_HANDLE_H_
00036 #define ROS_NODE_HANDLE_H_
00037 
00038 #include "../std_msgs/Time.h"
00039 #include "../rosserial_msgs/TopicInfo.h"
00040 #include "../rosserial_msgs/Log.h"
00041 #include "../rosserial_msgs/RequestParam.h"
00042 
00043 #define SYNC_SECONDS        5
00044 
00045 #define MODE_FIRST_FF       0
00046 #define MODE_SECOND_FF      1
00047 #define MODE_TOPIC_L        2   // waiting for topic id
00048 #define MODE_TOPIC_H        3
00049 #define MODE_SIZE_L         4   // waiting for message size
00050 #define MODE_SIZE_H         5
00051 #define MODE_MESSAGE        6
00052 #define MODE_CHECKSUM       7
00053 
00054 #define MSG_TIMEOUT 20  //20 milliseconds to recieve all of message data
00055 
00056 #include "node_output.h"
00057 
00058 #include "publisher.h"
00059 #include "msg_receiver.h"
00060 #include "subscriber.h"
00061 #include "rosserial_ids.h"
00062 #include "service_server.h"
00063 
00064 namespace ros {
00065 
00066   using rosserial_msgs::TopicInfo;
00067 
00068   /* Node Handle */
00069   template<class Hardware,
00070            int MAX_SUBSCRIBERS=25,
00071            int MAX_PUBLISHERS=25,
00072            int INPUT_SIZE=512,
00073            int OUTPUT_SIZE=512>
00074   class NodeHandle_
00075   {
00076     protected:
00077       Hardware hardware_;
00078       NodeOutput<Hardware, OUTPUT_SIZE> no_;
00079 
00080       /* time used for syncing */
00081       unsigned long rt_time;
00082 
00083       /* used for computing current time */
00084       unsigned long sec_offset, nsec_offset;
00085 
00086       unsigned char message_in[INPUT_SIZE];
00087 
00088       Publisher * publishers[MAX_PUBLISHERS];
00089       MsgReceiver * receivers[MAX_SUBSCRIBERS];
00090 
00091       /*
00092        * Setup Functions
00093        */
00094     public:
00095       NodeHandle_() : no_(&hardware_) {}
00096       
00097       Hardware* getHardware(){
00098         return &hardware_;
00099       }
00100 
00101       /* Start serial, initialize buffers */
00102       void initNode(){
00103         hardware_.init();
00104         mode_ = 0;
00105         bytes_ = 0;
00106         index_ = 0;
00107         topic_ = 0;
00108         total_receivers=0;
00109       };
00110 
00111     protected:
00112       //State machine variables for spinOnce
00113       int mode_;
00114       int bytes_;
00115       int topic_;
00116       int index_;
00117       int checksum_;
00118 
00119       int total_receivers;
00120 
00121       /* used for syncing the time */
00122       unsigned long last_sync_time;
00123       unsigned long last_sync_receive_time;
00124       unsigned long last_msg_timeout_time;
00125 
00126       bool registerReceiver(MsgReceiver* rcv){
00127         if (total_receivers >= MAX_SUBSCRIBERS)
00128           return false;
00129         receivers[total_receivers] = rcv;
00130         rcv->id_ = 100+total_receivers;
00131         total_receivers++;
00132         return true;
00133       }
00134 
00135     public:
00136       /* This function goes in your loop() function, it handles
00137        *  serial input and callbacks for subscribers.
00138        */
00139 
00140       virtual void spinOnce(){
00141 
00142         /* restart if timed out */
00143         unsigned long c_time = hardware_.time();
00144         if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
00145             no_.setConfigured(false);
00146          }
00147          
00148         /* reset if message has timed out */
00149         if ( mode_ != MODE_FIRST_FF){ 
00150           if (c_time > last_msg_timeout_time){
00151             mode_ = MODE_FIRST_FF;
00152           }
00153         }
00154 
00155         /* while available buffer, read data */
00156         while( true )
00157         {
00158           int data = hardware_.read();
00159           if( data < 0 )
00160             break;
00161           checksum_ += data;
00162           if( mode_ == MODE_MESSAGE ){        /* message data being recieved */
00163             message_in[index_++] = data;
00164             bytes_--;
00165             if(bytes_ == 0)                   /* is message complete? if so, checksum */
00166               mode_ = MODE_CHECKSUM;
00167           }else if( mode_ == MODE_FIRST_FF ){
00168             if(data == 0xff){
00169               mode_++;
00170               last_msg_timeout_time = c_time + MSG_TIMEOUT;
00171             }
00172           }else if( mode_ == MODE_SECOND_FF ){
00173             if(data == 0xff){
00174               mode_++;
00175             }else{
00176               mode_ = MODE_FIRST_FF;
00177             }
00178           }else if( mode_ == MODE_TOPIC_L ){  /* bottom half of topic id */
00179             topic_ = data;
00180             mode_++;
00181             checksum_ = data;                 /* first byte included in checksum */
00182           }else if( mode_ == MODE_TOPIC_H ){  /* top half of topic id */
00183             topic_ += data<<8;
00184             mode_++;
00185           }else if( mode_ == MODE_SIZE_L ){   /* bottom half of message size */
00186             bytes_ = data;
00187             index_ = 0;
00188             mode_++;
00189           }else if( mode_ == MODE_SIZE_H ){   /* top half of message size */
00190             bytes_ += data<<8;
00191             mode_ = MODE_MESSAGE;
00192             if(bytes_ == 0)
00193               mode_ = MODE_CHECKSUM;
00194           }else if( mode_ == MODE_CHECKSUM ){ /* do checksum */
00195             if( (checksum_%256) == 255){
00196               if(topic_ == TOPIC_NEGOTIATION){
00197                 requestSyncTime();
00198                 negotiateTopics();
00199                 last_sync_time = c_time;
00200                 last_sync_receive_time = c_time;
00201               }else if(topic_ == TopicInfo::ID_TIME){
00202                 syncTime(message_in);
00203               }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){
00204                   req_param_resp.deserialize(message_in);
00205                   param_recieved= true;
00206               }else{
00207                 if(receivers[topic_-100])
00208                   receivers[topic_-100]->receive( message_in );
00209               }
00210             }
00211             mode_ = MODE_FIRST_FF;
00212           }
00213         }
00214 
00215         /* occasionally sync time */
00216         if( no_.configured() && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){
00217           requestSyncTime();
00218           last_sync_time = c_time;
00219         }
00220       }
00221 
00222       /* Are we connected to the PC? */
00223       bool connected() {
00224         return no_.configured();
00225       };
00226 
00227       /*
00228        * Time functions
00229        */
00230 
00231       void requestSyncTime()
00232       {
00233         std_msgs::Time t;
00234         no_.publish( rosserial_msgs::TopicInfo::ID_TIME, &t);
00235         rt_time = hardware_.time();
00236       }
00237 
00238       void syncTime( unsigned char * data )
00239       {
00240         std_msgs::Time t;
00241         unsigned long offset = hardware_.time() - rt_time;
00242 
00243         t.deserialize(data);
00244 
00245         t.data.sec += offset/1000;
00246         t.data.nsec += (offset%1000)*1000000UL;
00247 
00248         this->setNow(t.data);
00249         last_sync_receive_time = hardware_.time();
00250       }
00251 
00252       Time now(){
00253         unsigned long ms = hardware_.time();
00254         Time current_time;
00255         current_time.sec = ms/1000 + sec_offset;
00256         current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
00257         normalizeSecNSec(current_time.sec, current_time.nsec);
00258         return current_time;
00259       }
00260 
00261       void setNow( Time & new_now )
00262       {
00263         unsigned long ms = hardware_.time();
00264         sec_offset = new_now.sec - ms/1000 - 1;
00265         nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
00266         normalizeSecNSec(sec_offset, nsec_offset);
00267       }
00268 
00269       /*
00270        * Registration 
00271        */
00272 
00273       bool advertise(Publisher & p)
00274       {
00275         int i;
00276         for(i = 0; i < MAX_PUBLISHERS; i++)
00277         {
00278           if(publishers[i] == 0) // empty slot
00279           {
00280             publishers[i] = &p;
00281             p.id_ = i+100+MAX_SUBSCRIBERS;
00282             p.no_ = &this->no_;
00283             return true;
00284           }
00285         }
00286         return false;
00287       }
00288 
00289       /* Register a subscriber with the node */
00290       template<typename MsgT>
00291         bool subscribe(Subscriber< MsgT> &s){
00292         return registerReceiver((MsgReceiver*) &s);
00293       }
00294 
00295       template<typename SrvReq, typename SrvResp>
00296       bool advertiseService(ServiceServer<SrvReq,SrvResp>& srv){
00297         srv.no_ = &no_;
00298         return registerReceiver((MsgReceiver*) &srv);
00299       }
00300 
00301       void negotiateTopics()
00302       {
00303         no_.setConfigured(true);
00304 
00305         rosserial_msgs::TopicInfo ti;
00306         int i;
00307         for(i = 0; i < MAX_PUBLISHERS; i++)
00308         {
00309           if(publishers[i] != 0) // non-empty slot
00310           {
00311             ti.topic_id = publishers[i]->id_;
00312             ti.topic_name = (char *) publishers[i]->topic_;
00313             ti.message_type = (char *) publishers[i]->msg_->getType();
00314             no_.publish( TOPIC_PUBLISHERS, &ti );
00315           }
00316         }
00317         for(i = 0; i < MAX_SUBSCRIBERS; i++)
00318         {
00319           if(receivers[i] != 0) // non-empty slot
00320           {
00321             ti.topic_id = receivers[i]->id_;
00322             ti.topic_name = (char *) receivers[i]->topic_;
00323             ti.message_type = (char *) receivers[i]->getMsgType();
00324             no_.publish( TOPIC_SUBSCRIBERS, &ti );
00325           }
00326         }
00327       }
00328 
00329       /*
00330        * Logging
00331        */
00332 
00333     private:
00334       void log(char byte, const char * msg){
00335         rosserial_msgs::Log l;
00336         l.level= byte;
00337         l.msg = (char*)msg;
00338         this->no_.publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
00339       }
00340 
00341     public:
00342       void logdebug(const char* msg){
00343         log(rosserial_msgs::Log::DEBUG, msg);
00344       }
00345       void loginfo(const char * msg){
00346         log(rosserial_msgs::Log::INFO, msg);
00347       }
00348       void logwarn(const char *msg){
00349         log(rosserial_msgs::Log::WARN, msg);
00350       }
00351       void logerror(const char*msg){
00352         log(rosserial_msgs::Log::ERROR, msg);
00353       }
00354       void logfatal(const char*msg){
00355         log(rosserial_msgs::Log::FATAL, msg);
00356       }
00357 
00358 
00359       /*
00360        * Retrieve Parameters
00361        */
00362 
00363     private:
00364       bool param_recieved;
00365       rosserial_msgs::RequestParamResponse req_param_resp;
00366 
00367       bool requestParam(const char * name, int time_out =  1000){
00368         param_recieved = false;
00369         rosserial_msgs::RequestParamRequest req;
00370         req.name  = (char*)name;
00371         no_.publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
00372         int end_time = hardware_.time();
00373         while(!param_recieved ){
00374           spinOnce();
00375           if (end_time > hardware_.time()) return false;
00376         }
00377         return true;
00378       }
00379 
00380     public:
00381       bool getParam(const char* name, int* param, int length =1){
00382         if (requestParam(name) ){
00383           if (length == req_param_resp.ints_length){
00384             //copy it over
00385             for(int i=0; i<length; i++)
00386               param[i] = req_param_resp.ints[i];
00387             return true;
00388           }
00389         }
00390         return false;
00391       }
00392       bool getParam(const char* name, float* param, int length=1){
00393         if (requestParam(name) ){
00394           if (length == req_param_resp.floats_length){
00395             //copy it over
00396             for(int i=0; i<length; i++) 
00397               param[i] = req_param_resp.floats[i];
00398             return true;
00399           }
00400         }
00401         return false;
00402       }
00403       bool getParam(const char* name, char** param, int length=1){
00404         if (requestParam(name) ){
00405           if (length == req_param_resp.strings_length){
00406             //copy it over
00407             for(int i=0; i<length; i++)
00408               strcpy(param[i],req_param_resp.strings[i]);
00409             return true;
00410           }
00411         }
00412         return false;
00413       }  
00414   };
00415 
00416 }
00417 
00418 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


traxbot_robot
Author(s): André Gonçalves Araújo
autogenerated on Fri Feb 1 2013 13:21:12