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 #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 "msg.h"
00057
00058 namespace ros {
00059
00060 class NodeHandleBase_{
00061 public:
00062 virtual int publish(int id, const Msg* msg)=0;
00063 virtual int spinOnce()=0;
00064 virtual bool connected()=0;
00065 };
00066
00067 }
00068
00069 #include "publisher.h"
00070 #include "subscriber.h"
00071 #include "service_server.h"
00072 #include "service_client.h"
00073
00074 namespace ros {
00075
00076 using rosserial_msgs::TopicInfo;
00077
00078
00079 template<class Hardware,
00080 int MAX_SUBSCRIBERS=25,
00081 int MAX_PUBLISHERS=25,
00082 int INPUT_SIZE=512,
00083 int OUTPUT_SIZE=512>
00084 class NodeHandle_ : public NodeHandleBase_
00085 {
00086 protected:
00087 Hardware hardware_;
00088
00089
00090 unsigned long rt_time;
00091
00092
00093 unsigned long sec_offset, nsec_offset;
00094
00095 unsigned char message_in[INPUT_SIZE];
00096 unsigned char message_out[OUTPUT_SIZE];
00097
00098 Publisher * publishers[MAX_PUBLISHERS];
00099 Subscriber_ * subscribers[MAX_SUBSCRIBERS];
00100
00101
00102
00103
00104 public:
00105 NodeHandle_() : configured_(false) {}
00106
00107 Hardware* getHardware(){
00108 return &hardware_;
00109 }
00110
00111
00112 void initNode(){
00113 hardware_.init();
00114 mode_ = 0;
00115 bytes_ = 0;
00116 index_ = 0;
00117 topic_ = 0;
00118 };
00119
00120 protected:
00121
00122 int mode_;
00123 int bytes_;
00124 int topic_;
00125 int index_;
00126 int checksum_;
00127
00128 bool configured_;
00129
00130
00131 unsigned long last_sync_time;
00132 unsigned long last_sync_receive_time;
00133 unsigned long last_msg_timeout_time;
00134
00135 public:
00136
00137
00138
00139
00140 virtual int spinOnce(){
00141
00142
00143 unsigned long c_time = hardware_.time();
00144 if( (c_time - last_sync_receive_time) > (SYNC_SECONDS*2200) ){
00145 configured_ = false;
00146 }
00147
00148
00149 if ( mode_ != MODE_FIRST_FF){
00150 if (c_time > last_msg_timeout_time){
00151 mode_ = MODE_FIRST_FF;
00152 }
00153 }
00154
00155
00156 while( true )
00157 {
00158 int data = hardware_.read();
00159 if( data < 0 )
00160 break;
00161 checksum_ += data;
00162 if( mode_ == MODE_MESSAGE ){
00163 message_in[index_++] = data;
00164 bytes_--;
00165 if(bytes_ == 0)
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 ){
00179 topic_ = data;
00180 mode_++;
00181 checksum_ = data;
00182 }else if( mode_ == MODE_TOPIC_H ){
00183 topic_ += data<<8;
00184 mode_++;
00185 }else if( mode_ == MODE_SIZE_L ){
00186 bytes_ = data;
00187 index_ = 0;
00188 mode_++;
00189 }else if( mode_ == MODE_SIZE_H ){
00190 bytes_ += data<<8;
00191 mode_ = MODE_MESSAGE;
00192 if(bytes_ == 0)
00193 mode_ = MODE_CHECKSUM;
00194 }else if( mode_ == MODE_CHECKSUM ){
00195 mode_ = MODE_FIRST_FF;
00196 if( (checksum_%256) == 255){
00197 if(topic_ == TopicInfo::ID_PUBLISHER){
00198 requestSyncTime();
00199 negotiateTopics();
00200 last_sync_time = c_time;
00201 last_sync_receive_time = c_time;
00202 return -1;
00203 }else if(topic_ == TopicInfo::ID_TIME){
00204 syncTime(message_in);
00205 }else if (topic_ == TopicInfo::ID_PARAMETER_REQUEST){
00206 req_param_resp.deserialize(message_in);
00207 param_recieved= true;
00208 }else{
00209 if(subscribers[topic_-100])
00210 subscribers[topic_-100]->callback( message_in );
00211 }
00212 }
00213 }
00214 }
00215
00216
00217 if( configured_ && ((c_time-last_sync_time) > (SYNC_SECONDS*500) )){
00218 requestSyncTime();
00219 last_sync_time = c_time;
00220 }
00221
00222 return 0;
00223 }
00224
00225
00226 virtual bool connected() {
00227 return configured_;
00228 };
00229
00230
00231
00232
00233
00234 void requestSyncTime()
00235 {
00236 std_msgs::Time t;
00237 publish(TopicInfo::ID_TIME, &t);
00238 rt_time = hardware_.time();
00239 }
00240
00241 void syncTime( unsigned char * data )
00242 {
00243 std_msgs::Time t;
00244 unsigned long offset = hardware_.time() - rt_time;
00245
00246 t.deserialize(data);
00247 t.data.sec += offset/1000;
00248 t.data.nsec += (offset%1000)*1000000UL;
00249
00250 this->setNow(t.data);
00251 last_sync_receive_time = hardware_.time();
00252 }
00253
00254 Time now(){
00255 unsigned long ms = hardware_.time();
00256 Time current_time;
00257 current_time.sec = ms/1000 + sec_offset;
00258 current_time.nsec = (ms%1000)*1000000UL + nsec_offset;
00259 normalizeSecNSec(current_time.sec, current_time.nsec);
00260 return current_time;
00261 }
00262
00263 void setNow( Time & new_now )
00264 {
00265 unsigned long ms = hardware_.time();
00266 sec_offset = new_now.sec - ms/1000 - 1;
00267 nsec_offset = new_now.nsec - (ms%1000)*1000000UL + 1000000000UL;
00268 normalizeSecNSec(sec_offset, nsec_offset);
00269 }
00270
00271
00272
00273
00274
00275
00276 bool advertise(Publisher & p)
00277 {
00278 for(int i = 0; i < MAX_PUBLISHERS; i++){
00279 if(publishers[i] == 0){
00280 publishers[i] = &p;
00281 p.id_ = i+100+MAX_SUBSCRIBERS;
00282 p.nh_ = this;
00283 return true;
00284 }
00285 }
00286 return false;
00287 }
00288
00289
00290 template<typename MsgT>
00291 bool subscribe(Subscriber< MsgT> & s){
00292 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00293 if(subscribers[i] == 0){
00294 subscribers[i] = (Subscriber_*) &s;
00295 s.id_ = i+100;
00296 return true;
00297 }
00298 }
00299 return false;
00300 }
00301
00302
00303 template<typename MReq, typename MRes>
00304 bool advertiseService(ServiceServer<MReq,MRes>& srv){
00305 bool v = advertise(srv.pub);
00306 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00307 if(subscribers[i] == 0){
00308 subscribers[i] = (Subscriber_*) &srv;
00309 srv.id_ = i+100;
00310 return v;
00311 }
00312 }
00313 return false;
00314 }
00315
00316
00317 template<typename MReq, typename MRes>
00318 bool serviceClient(ServiceClient<MReq, MRes>& srv){
00319 bool v = advertise(srv.pub);
00320 for(int i = 0; i < MAX_SUBSCRIBERS; i++){
00321 if(subscribers[i] == 0){
00322 subscribers[i] = (Subscriber_*) &srv;
00323 srv.id_ = i+100;
00324 return v;
00325 }
00326 }
00327 return false;
00328 }
00329
00330 void negotiateTopics()
00331 {
00332 configured_ = true;
00333
00334 rosserial_msgs::TopicInfo ti;
00335 int i;
00336 for(i = 0; i < MAX_PUBLISHERS; i++)
00337 {
00338 if(publishers[i] != 0)
00339 {
00340 ti.topic_id = publishers[i]->id_;
00341 ti.topic_name = (char *) publishers[i]->topic_;
00342 ti.message_type = (char *) publishers[i]->msg_->getType();
00343 ti.md5sum = (char *) publishers[i]->msg_->getMD5();
00344 ti.buffer_size = OUTPUT_SIZE;
00345 publish( publishers[i]->getEndpointType(), &ti );
00346 }
00347 }
00348 for(i = 0; i < MAX_SUBSCRIBERS; i++)
00349 {
00350 if(subscribers[i] != 0)
00351 {
00352 ti.topic_id = subscribers[i]->id_;
00353 ti.topic_name = (char *) subscribers[i]->topic_;
00354 ti.message_type = (char *) subscribers[i]->getMsgType();
00355 ti.md5sum = (char *) subscribers[i]->getMsgMD5();
00356 ti.buffer_size = INPUT_SIZE;
00357 publish( subscribers[i]->getEndpointType(), &ti );
00358 }
00359 }
00360 }
00361
00362 virtual int publish(int id, const Msg * msg)
00363 {
00364 if(!configured_) return 0;
00365
00366
00367 int l = msg->serialize(message_out+6);
00368
00369
00370 message_out[0] = 0xff;
00371 message_out[1] = 0xff;
00372 message_out[2] = (unsigned char) id&255;
00373 message_out[3] = (unsigned char) id>>8;
00374 message_out[4] = (unsigned char) l&255;
00375 message_out[5] = ((unsigned char) l>>8);
00376
00377
00378 int chk = 0;
00379 for(int i =2; i<l+6; i++)
00380 chk += message_out[i];
00381 l += 6;
00382 message_out[l++] = 255 - (chk%256);
00383
00384 if( l <= OUTPUT_SIZE ){
00385 hardware_.write(message_out, l);
00386 return l;
00387 }else{
00388 logerror("Message from device dropped: message larger than buffer.");
00389 }
00390 }
00391
00392
00393
00394
00395
00396 private:
00397 void log(char byte, const char * msg){
00398 rosserial_msgs::Log l;
00399 l.level= byte;
00400 l.msg = (char*)msg;
00401 publish(rosserial_msgs::TopicInfo::ID_LOG, &l);
00402 }
00403
00404 public:
00405 void logdebug(const char* msg){
00406 log(rosserial_msgs::Log::DEBUG, msg);
00407 }
00408 void loginfo(const char * msg){
00409 log(rosserial_msgs::Log::INFO, msg);
00410 }
00411 void logwarn(const char *msg){
00412 log(rosserial_msgs::Log::WARN, msg);
00413 }
00414 void logerror(const char*msg){
00415 log(rosserial_msgs::Log::ERROR, msg);
00416 }
00417 void logfatal(const char*msg){
00418 log(rosserial_msgs::Log::FATAL, msg);
00419 }
00420
00421
00422
00423
00424
00425 private:
00426 bool param_recieved;
00427 rosserial_msgs::RequestParamResponse req_param_resp;
00428
00429 bool requestParam(const char * name, int time_out = 1000){
00430 param_recieved = false;
00431 rosserial_msgs::RequestParamRequest req;
00432 req.name = (char*)name;
00433 publish(TopicInfo::ID_PARAMETER_REQUEST, &req);
00434 int end_time = hardware_.time();
00435 while(!param_recieved ){
00436 spinOnce();
00437 if (end_time > hardware_.time()) return false;
00438 }
00439 return true;
00440 }
00441
00442 public:
00443 bool getParam(const char* name, int* param, int length =1){
00444 if (requestParam(name) ){
00445 if (length == req_param_resp.ints_length){
00446
00447 for(int i=0; i<length; i++)
00448 param[i] = req_param_resp.ints[i];
00449 return true;
00450 }
00451 }
00452 return false;
00453 }
00454 bool getParam(const char* name, float* param, int length=1){
00455 if (requestParam(name) ){
00456 if (length == req_param_resp.floats_length){
00457
00458 for(int i=0; i<length; i++)
00459 param[i] = req_param_resp.floats[i];
00460 return true;
00461 }
00462 }
00463 return false;
00464 }
00465 bool getParam(const char* name, char** param, int length=1){
00466 if (requestParam(name) ){
00467 if (length == req_param_resp.strings_length){
00468
00469 for(int i=0; i<length; i++)
00470 strcpy(param[i],req_param_resp.strings[i]);
00471 return true;
00472 }
00473 }
00474 return false;
00475 }
00476 };
00477
00478 }
00479
00480 #endif