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 <stdint.h>
00039 
00040 #include "std_msgs/Time.h"
00041 #include "rosserial_msgs/TopicInfo.h"
00042 #include "rosserial_msgs/Log.h"
00043 #include "rosserial_msgs/RequestParam.h"
00044 
00045 #include "ros/msg.h"
00046 
00047 namespace ros {
00048 
00049   class NodeHandleBase_{
00050     public:
00051       virtual int publish(int id, const Msg* msg)=0;
00052       virtual int spinOnce()=0;
00053       virtual bool connected()=0;
00054     };
00055 }
00056 
00057 #include "ros/publisher.h"
00058 #include "ros/subscriber.h"
00059 #include "ros/service_server.h"
00060 #include "ros/service_client.h"
00061 
00062 namespace ros {
00063 
00064   const uint8_t SYNC_SECONDS  = 5;
00065   const uint8_t MODE_FIRST_FF = 0;
00066   /*
00067    * The second sync byte is a protocol version. It's value is 0xff for the first
00068    * version of the rosserial protocol (used up to hydro), 0xfe for the second version
00069    * (introduced in hydro), 0xfd for the next, and so on. Its purpose is to enable
00070    * detection of mismatched protocol versions (e.g. hydro rosserial_python with groovy
00071    * rosserial_arduino. It must be changed in both this file and in
00072    * rosserial_python/src/rosserial_python/SerialClient.py
00073    */
00074   const uint8_t MODE_PROTOCOL_VER   = 1;
00075   const uint8_t PROTOCOL_VER1       = 0xff; // through groovy
00076   const uint8_t PROTOCOL_VER2       = 0xfe; // in hydro
00077   const uint8_t PROTOCOL_VER        = PROTOCOL_VER2;
00078   const uint8_t MODE_SIZE_L         = 2;
00079   const uint8_t MODE_SIZE_H         = 3;
00080   const uint8_t MODE_SIZE_CHECKSUM  = 4;    // checksum for msg size received from size L and H
00081   const uint8_t MODE_TOPIC_L        = 5;    // waiting for topic id
00082   const uint8_t MODE_TOPIC_H        = 6;
00083   const uint8_t MODE_MESSAGE        = 7;
00084   const uint8_t MODE_MSG_CHECKSUM   = 8;    // checksum for msg and topic id
00085 
00086 
00087   const uint8_t SERIAL_MSG_TIMEOUT  = 20;   // 20 milliseconds to recieve all of message data
00088 
00089   using rosserial_msgs::TopicInfo;
00090 
00091   /* Node Handle */
00092   template<class Hardware,
00093            int MAX_SUBSCRIBERS=25,
00094            int MAX_PUBLISHERS=25,
00095            int INPUT_SIZE=512,
00096            int OUTPUT_SIZE=512>
00097   class NodeHandle_ : public NodeHandleBase_
00098   {
00099     protected:
00100       Hardware hardware_;
00101 
00102       /* time used for syncing */
00103       uint32_t rt_time;
00104 
00105       /* used for computing current time */
00106       uint32_t sec_offset, nsec_offset;
00107 
00108       uint8_t message_in[INPUT_SIZE];
00109       uint8_t message_out[OUTPUT_SIZE];
00110 
00111       Publisher * publishers[MAX_PUBLISHERS];
00112       Subscriber_ * subscribers[MAX_SUBSCRIBERS];
00113 
00114       /*
00115        * Setup Functions
00116        */
00117     public:
00118       NodeHandle_() : configured_(false) {
00119 
00120         for(unsigned int i=0; i< MAX_PUBLISHERS; i++)
00121            publishers[i] = 0;
00122 
00123         for(unsigned int i=0; i< MAX_SUBSCRIBERS; i++)
00124            subscribers[i] = 0;
00125 
00126         for(unsigned int i=0; i< INPUT_SIZE; i++)
00127            message_in[i] = 0;
00128 
00129         for(unsigned int i=0; i< OUTPUT_SIZE; i++)
00130            message_out[i] = 0;
00131 
00132         req_param_resp.ints_length = 0;
00133         req_param_resp.ints = NULL;
00134         req_param_resp.floats_length = 0;
00135         req_param_resp.floats = NULL;
00136         req_param_resp.ints_length = 0;
00137         req_param_resp.ints = NULL;
00138       }
00139 
00140       Hardware* getHardware(){
00141         return &hardware_;
00142       }
00143 
00144       /* Start serial, initialize buffers */
00145       void initNode(){
00146         hardware_.init();
00147         mode_ = 0;
00148         bytes_ = 0;
00149         index_ = 0;
00150         topic_ = 0;
00151       };
00152 
00153       /* Start a named port, which may be network server IP, initialize buffers */
00154       void initNode(char *portName){
00155         hardware_.init(portName);
00156         mode_ = 0;
00157         bytes_ = 0;
00158         index_ = 0;
00159         topic_ = 0;
00160       };
00161 
00162     protected:
00163       //State machine variables for spinOnce
00164       int mode_;
00165       int bytes_;
00166       int topic_;
00167       int index_;
00168       int checksum_;
00169 
00170       bool configured_;
00171 
00172       /* used for syncing the time */
00173       uint32_t last_sync_time;
00174       uint32_t last_sync_receive_time;
00175       uint32_t last_msg_timeout_time;
00176 
00177     public:
00178       /* This function goes in your loop() function, it handles
00179        *  serial input and callbacks for subscribers.
00180        */
00181 
00182 
00183       virtual int spinOnce(){
00184 
00185         /* restart if timed out */
00186         uint32_t c_time = hardware_.time();
00187         if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
00188             configured_ = false;
00189          }
00190 
00191         /* reset if message has timed out */
00192         if ( mode_ != MODE_FIRST_FF){
00193           if (c_time > last_msg_timeout_time){
00194             mode_ = MODE_FIRST_FF;
00195           }
00196         }
00197 
00198         /* while available buffer, read data */
00199         while( true )
00200         {
00201           int data = hardware_.read();
00202           if( data < 0 )
00203             break;
00204           checksum_ += data;
00205           if( mode_ == MODE_MESSAGE ){        /* message data being recieved */
00206             message_in[index_++] = data;
00207             bytes_--;
00208             if(bytes_ == 0)                  /* is message complete? if so, checksum */
00209               mode_ = MODE_MSG_CHECKSUM;
00210           }else if( mode_ == MODE_FIRST_FF ){
00211             if(data == 0xff){
00212               mode_++;
00213               last_msg_timeout_time = c_time + SERIAL_MSG_TIMEOUT;
00214             }
00215             else if( hardware_.time() - c_time > (SYNC_SECONDS*1000)){
00216               /* We have been stuck in spinOnce too long, return error */
00217               configured_=false;
00218               return -2;
00219             }
00220           }else if( mode_ == MODE_PROTOCOL_VER ){
00221             if(data == PROTOCOL_VER){
00222               mode_++;
00223             }else{
00224               mode_ = MODE_FIRST_FF;
00225               if (configured_ == false)
00226                   requestSyncTime();    /* send a msg back showing our protocol version */
00227             }
00228           }else if( mode_ == MODE_SIZE_L ){   /* bottom half of message size */
00229             bytes_ = data;
00230             index_ = 0;
00231             mode_++;
00232             checksum_ = data;               /* first byte for calculating size checksum */
00233           }else if( mode_ == MODE_SIZE_H ){   /* top half of message size */
00234             bytes_ += data<<8;
00235             mode_++;
00236           }else if( mode_ == MODE_SIZE_CHECKSUM ){
00237             if( (checksum_%256) == 255)
00238               mode_++;
00239             else
00240               mode_ = MODE_FIRST_FF;          /* Abandon the frame if the msg len is wrong */
00241           }else if( mode_ == MODE_TOPIC_L ){  /* bottom half of topic id */
00242             topic_ = data;
00243             mode_++;
00244             checksum_ = data;               /* first byte included in checksum */
00245           }else if( mode_ == MODE_TOPIC_H ){  /* top half of topic id */
00246             topic_ += data<<8;
00247             mode_ = MODE_MESSAGE;
00248             if(bytes_ == 0)
00249               mode_ = MODE_MSG_CHECKSUM;
00250           }else if( mode_ == MODE_MSG_CHECKSUM ){ /* do checksum */
00251             mode_ = MODE_FIRST_FF;
00252             if( (checksum_%256) == 255){
00253               if(topic_ == TopicInfo::ID_PUBLISHER){
00254                 requestSyncTime();
00255                 negotiateTopics();
00256                 last_sync_time = c_time;
00257                 last_sync_receive_time = c_time;
00258                 return -1;
00259               }else if(topic_ == TopicInfo::ID_TIME){
00260                 syncTime(message_in);
00261               }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){
00262                   req_param_resp.deserialize(message_in);
00263                   param_recieved= true;
00264               }else if(topic_ == TopicInfo::ID_TX_STOP){
00265                   configured_ = false;
00266               }else{
00267                 if(subscribers[topic_-100])
00268                   subscribers[topic_-100]->callback( message_in );
00269               }
00270             }
00271           }
00272         }
00273 
00274         /* occasionally sync time */
00275         if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){
00276           requestSyncTime();
00277           last_sync_time = c_time;
00278         }
00279 
00280         return 0;
00281       }
00282 
00283 
00284       /* Are we connected to the PC? */
00285       virtual bool connected() {
00286         return configured_;
00287       };
00288 
00289       /********************************************************************
00290        * Time functions
00291        */
00292 
00293       void requestSyncTime()
00294       {
00295         std_msgs::Time t;
00296         publish(TopicInfo::ID_TIME, &t);
00297         rt_time = hardware_.time();
00298       }
00299 
00300       void syncTime(uint8_t * data)
00301       {
00302         std_msgs::Time t;
00303         uint32_t offset = hardware_.time() - rt_time;
00304 
00305         t.deserialize(data);
00306         t.data.sec += offset/1000;
00307         t.data.nsec += (offset%1000)*1000000UL;
00308 
00309         this->setNow(t.data);
00310         last_sync_receive_time = hardware_.time();
00311       }
00312 
00313       Time now()
00314       {
00315         uint32_t ms = hardware_.time();
00316         Time current_time;
00317         current_time.sec = ms/1000 + sec_offset;
00318         current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
00319         normalizeSecNSec(current_time.sec, current_time.nsec);
00320         return current_time;
00321       }
00322 
00323       void setNow( Time & new_now )
00324       {
00325         uint32_t ms = hardware_.time();
00326         sec_offset = new_now.sec - ms/1000 - 1;
00327         nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
00328         normalizeSecNSec(sec_offset, nsec_offset);
00329       }
00330 
00331       /********************************************************************
00332        * Topic Management
00333        */
00334 
00335       /* Register a new publisher */
00336       bool advertise(Publisher & p)
00337       {
00338         for(int i = 0; i < MAX_PUBLISHERS; i++){
00339           if(publishers[i] == 0){ // empty slot
00340             publishers[i] = &p;
00341             p.id_ = i+100+MAX_SUBSCRIBERS;
00342             p.nh_ = this;
00343             return true;
00344           }
00345         }
00346         return false;
00347       }
00348 
00349       /* Register a new subscriber */
00350       template<typename SubscriberT>
00351       bool subscribe(SubscriberT& s){
00352         for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00353           if(subscribers[i] == 0){ // empty slot
00354             subscribers[i] = static_cast<Subscriber_*>(&s);
00355             s.id_ = i+100;
00356             return true;
00357           }
00358         }
00359         return false;
00360       }
00361 
00362       /* Register a new Service Server */
00363       template<typename MReq, typename MRes, typename ObjT>
00364       bool advertiseService(ServiceServer<MReq,MRes,ObjT>& srv){
00365         bool v = advertise(srv.pub);
00366         for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00367           if(subscribers[i] == 0){ // empty slot
00368             subscribers[i] = static_cast<Subscriber_*>(&srv);
00369             srv.id_ = i+100;
00370             return v;
00371           }
00372         }
00373         return false;
00374       }
00375 
00376       /* Register a new Service Client */
00377       template<typename MReq, typename MRes>
00378       bool serviceClient(ServiceClient<MReq, MRes>& srv){
00379         bool v = advertise(srv.pub);
00380         for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00381           if(subscribers[i] == 0){ // empty slot
00382             subscribers[i] = static_cast<Subscriber_*>(&srv);
00383             srv.id_ = i+100;
00384             return v;
00385           }
00386         }
00387         return false;
00388       }
00389 
00390       void negotiateTopics()
00391       {
00392         rosserial_msgs::TopicInfo ti;
00393         int i;
00394         for(i = 0; i < MAX_PUBLISHERS; i++)
00395         {
00396           if(publishers[i] != 0) // non-empty slot
00397           {
00398             ti.topic_id = publishers[i]->id_;
00399             ti.topic_name = (char *) publishers[i]->topic_;
00400             ti.message_type = (char *) publishers[i]->msg_->getType();
00401             ti.md5sum = (char *) publishers[i]->msg_->getMD5();
00402             ti.buffer_size = OUTPUT_SIZE;
00403             publish( publishers[i]->getEndpointType(), &ti );
00404           }
00405         }
00406         for(i = 0; i < MAX_SUBSCRIBERS; i++)
00407         {
00408           if(subscribers[i] != 0) // non-empty slot
00409           {
00410             ti.topic_id = subscribers[i]->id_;
00411             ti.topic_name = (char *) subscribers[i]->topic_;
00412             ti.message_type = (char *) subscribers[i]->getMsgType();
00413             ti.md5sum = (char *) subscribers[i]->getMsgMD5();
00414             ti.buffer_size = INPUT_SIZE;
00415             publish( subscribers[i]->getEndpointType(), &ti );
00416           }
00417         }
00418         configured_ = true;
00419       }
00420 
00421       virtual int publish(int id, const Msg * msg)
00422       {
00423         if(id >= 100 && !configured_)
00424           return 0;
00425 
00426         /* serialize message */
00427         int l = msg->serialize(message_out+7);
00428 
00429         /* setup the header */
00430         message_out[0] = 0xff;
00431         message_out[1] = PROTOCOL_VER;
00432         message_out[2] = (uint8_t) ((uint16_t)l&255);
00433         message_out[3] = (uint8_t) ((uint16_t)l>>8);
00434         message_out[4] = 255 - ((message_out[2] + message_out[3])%256);
00435         message_out[5] = (uint8_t) ((int16_t)id&255);
00436         message_out[6] = (uint8_t) ((int16_t)id>>8);
00437 
00438         /* calculate checksum */
00439         int chk = 0;
00440         for(int i =5; i<l+7; i++)
00441           chk += message_out[i];
00442         l += 7;
00443         message_out[l++] = 255 - (chk%256);
00444 
00445         if( l <= OUTPUT_SIZE ){
00446           hardware_.write(message_out, l);
00447           return l;
00448         }else{
00449           logerror("Message from device dropped: message larger than buffer.");
00450           return -1;
00451         }
00452       }
00453 
00454       /********************************************************************
00455        * Logging
00456        */
00457 
00458     private:
00459       void log(char byte, const char * msg){
00460         rosserial_msgs::Log l;
00461         l.level= byte;
00462         l.msg = (char*)msg;
00463         publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
00464       }
00465 
00466     public:
00467       void logdebug(const char* msg){
00468         log(rosserial_msgs::Log::ROSDEBUG, msg);
00469       }
00470       void loginfo(const char * msg){
00471         log(rosserial_msgs::Log::INFO, msg);
00472       }
00473       void logwarn(const char *msg){
00474         log(rosserial_msgs::Log::WARN, msg);
00475       }
00476       void logerror(const char*msg){
00477         log(rosserial_msgs::Log::ERROR, msg);
00478       }
00479       void logfatal(const char*msg){
00480         log(rosserial_msgs::Log::FATAL, msg);
00481       }
00482 
00483       /********************************************************************
00484        * Parameters
00485        */
00486 
00487     private:
00488       bool param_recieved;
00489       rosserial_msgs::RequestParamResponse req_param_resp;
00490 
00491       bool requestParam(const char * name, int time_out =  1000){
00492         param_recieved = false;
00493         rosserial_msgs::RequestParamRequest req;
00494         req.name  = (char*)name;
00495         publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
00496         uint32_t end_time = hardware_.time() + time_out;
00497         while(!param_recieved ){
00498           spinOnce();
00499           if (hardware_.time() > end_time) {
00500             logwarn("Failed to get param: timeout expired");
00501             return false;
00502           }
00503         }
00504         return true;
00505       }
00506 
00507     public:
00508       bool getParam(const char* name, int* param, int length =1, int timeout = 1000){
00509         if (requestParam(name, timeout) ){
00510           if (length == req_param_resp.ints_length){
00511             //copy it over
00512             for(int i=0; i<length; i++)
00513               param[i] = req_param_resp.ints[i];
00514             return true;
00515           } else {
00516             logwarn("Failed to get param: length mismatch");
00517           }
00518         }
00519         return false;
00520       }
00521       bool getParam(const char* name, float* param, int length=1, int timeout = 1000){
00522         if (requestParam(name, timeout) ){
00523           if (length == req_param_resp.floats_length){
00524             //copy it over
00525             for(int i=0; i<length; i++)
00526               param[i] = req_param_resp.floats[i];
00527             return true;
00528           } else {
00529             logwarn("Failed to get param: length mismatch");
00530           }
00531         }
00532         return false;
00533       }
00534       bool getParam(const char* name, char** param, int length=1, int timeout = 1000){
00535         if (requestParam(name, timeout) ){
00536           if (length == req_param_resp.strings_length){
00537             //copy it over
00538             for(int i=0; i<length; i++)
00539               strcpy(param[i],req_param_resp.strings[i]);
00540             return true;
00541           } else {
00542             logwarn("Failed to get param: length mismatch");
00543           }
00544         }
00545         return false;
00546       }
00547   };
00548 
00549 }
00550 
00551 #endif


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Sat Oct 7 2017 03:08:37