roseus.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, 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 products 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 // author: Kei Okada
00036 
00037 
00038 #include <stdio.h>
00039 #include <stdlib.h>
00040 #include <unistd.h>
00041 #include <string.h>
00042 #include <signal.h>
00043 #include <math.h>
00044 #include <time.h>
00045 #include <pthread.h>
00046 #include <setjmp.h>
00047 #include <errno.h>
00048 
00049 #include <list>
00050 #include <vector>
00051 #include <set>
00052 #include <string>
00053 #include <map>
00054 #include <sstream>
00055 
00056 #include <cstdio>
00057 #include <boost/thread/mutex.hpp>
00058 #include <boost/thread/condition.hpp>
00059 #include <boost/shared_ptr.hpp>
00060 #include <boost/algorithm/string.hpp>
00061 #include <boost/variant.hpp>
00062 #include <boost/foreach.hpp>
00063 
00064 #include <ros/init.h>
00065 #include <ros/time.h>
00066 #include <ros/rate.h>
00067 #include <ros/master.h>
00068 #include <ros/this_node.h>
00069 #include <ros/node_handle.h>
00070 #include <ros/service.h>
00071 #include <rospack/rospack.h>
00072 #include <ros/param.h>
00073 #include <ros/callback_queue.h>
00074 
00075 // for eus.h
00076 #define class   eus_class
00077 #define throw   eus_throw
00078 #define export  eus_export
00079 #define vector  eus_vector
00080 #define string  eus_string
00081 
00082 #include "eus.h"
00083 extern "C" {
00084   pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env);
00085   void register_roseus(){
00086     char modname[] = "___roseus";
00087     return add_module_initializer(modname, (pointer (*)())___roseus);}
00088   /* get_string is originally defined in lisp/c/makes.c, but it is also defined in Python.so linked from rospack.so
00089      to avoid confusion, we have to explictly re-define this method, specially for OSX */
00090   byte *get_string(register pointer s){
00091     if (isstring(s)) return(s->c.str.chars);
00092     if (issymbol(s)) return(s->c.sym.pname->c.str.chars);
00093     else error(E_NOSTRING); return NULL; }
00094 }
00095 
00096 #undef class
00097 #undef throw
00098 #undef export
00099 #undef vector
00100 #undef string
00101 
00102 namespace ros {
00103   namespace master {
00104     std::string g_uri;
00105     void init(const M_string& remappings);
00106   }
00107   namespace param {
00108     void init(const M_string& remappings);
00109   }
00110 }
00111 
00112 using namespace ros;
00113 using namespace std;
00114 
00115 #define isInstalledCheck \
00116   if( ! ros::ok() ) { error(E_USER,"You must call (ros::roseus \"name\") before creating the first NodeHandle"); }
00117 
00118 class RoseusStaticData
00119 {
00120 public:
00121   RoseusStaticData() {}
00122   ~RoseusStaticData() {
00123   }
00124   boost::shared_ptr<ros::NodeHandle> node;
00125   ros::Rate *rate;
00126   map<string, boost::shared_ptr<Publisher> > mapAdvertised; 
00127   map<string, boost::shared_ptr<Subscriber> > mapSubscribed; 
00128   map<string, boost::shared_ptr<ServiceServer> > mapServiced; 
00129   map<string, Timer > mapTimered; 
00130 
00131   map<string, boost::shared_ptr<NodeHandle> > mapHandle; 
00132 };
00133 
00134 static RoseusStaticData s_staticdata;
00135 static bool s_bInstalled = false;
00136 #define s_node s_staticdata.node
00137 #define s_rate s_staticdata.rate
00138 #define s_mapAdvertised s_staticdata.mapAdvertised
00139 #define s_mapSubscribed s_staticdata.mapSubscribed
00140 #define s_mapServiced s_staticdata.mapServiced
00141 #define s_mapTimered s_staticdata.mapTimered
00142 #define s_mapHandle s_staticdata.mapHandle
00143 
00144 pointer K_ROSEUS_MD5SUM,K_ROSEUS_DATATYPE,K_ROSEUS_DEFINITION,K_ROSEUS_SERIALIZATION_LENGTH,K_ROSEUS_SERIALIZE,K_ROSEUS_DESERIALIZE,K_ROSEUS_INIT,K_ROSEUS_GET,K_ROSEUS_REQUEST,K_ROSEUS_RESPONSE,K_ROSEUS_GROUPNAME,K_ROSEUS_ONESHOT,K_ROSEUS_LAST_EXPECTED,K_ROSEUS_LAST_REAL,K_ROSEUS_CURRENT_EXPECTED,K_ROSEUS_CURRENT_REAL,K_ROSEUS_LAST_DURATION,K_ROSEUS_SEC,K_ROSEUS_NSEC,QANON,QNOOUT,QREPOVERSION,QROSDEBUG,QROSINFO,QROSWARN,QROSERROR,QROSFATAL;
00145 extern pointer LAMCLOSURE;
00146 
00147 /***********************************************************
00148  *   Message wrapper
00149  ************************************************************/
00150 
00151 string getString(pointer message, pointer method) {
00152   context *ctx = current_ctx;
00153   pointer r, curclass;
00154   if ((pointer)findmethod(ctx,method,classof(message),&curclass)!=NIL) {
00155     r = csend(ctx,message,method,0);
00156   } else if ((pointer)findmethod(ctx,K_ROSEUS_GET,classof(message),&curclass) != NIL ) {
00157     r = csend(ctx,message,K_ROSEUS_GET,1,method);
00158   } else {
00159     r = NULL;
00160 #ifdef x86_64
00161     ROS_ERROR("could not find method %s for pointer %lx",
00162               get_string(method), (long unsigned int)message);
00163 #else
00164     ROS_ERROR("could not find method %s for pointer %x",
00165               get_string(method), (unsigned int)message);
00166 #endif
00167   }
00168   if ( !isstring(r) ) {
00169     pointer dest=(pointer)mkstream(ctx,K_OUT,makebuffer(64));
00170     prinx(ctx,message,dest);
00171     pointer str = makestring((char *)dest->c.stream.buffer->c.str.chars,
00172                              intval(dest->c.stream.count));
00173     ROS_ERROR("send %s to %s returns nil", get_string(method), get_string(str));
00174   }
00175   ROS_ASSERT(isstring(r));
00176   string ret = (char *)get_string(r);
00177   return ret;
00178 }
00179 
00180 int getInteger(pointer message, pointer method) {
00181   context *ctx = current_ctx;
00182   pointer a,curclass;
00183   vpush(message);
00184   a = (pointer)findmethod(ctx,method,classof(message),&curclass);
00185   if (a!=NIL) {
00186     pointer r = csend(ctx,message,method,0);
00187     vpop();                     // message
00188     return (ckintval(r));
00189   } else {
00190 #ifdef x86_64
00191     ROS_ERROR("could not find method %s for pointer %lx",
00192               get_string(method), (long unsigned int)message);
00193 #else
00194     ROS_ERROR("could not find method %s for pointer %x",
00195               get_string(method), (unsigned int)message);
00196 #endif
00197     vpop();                     // message
00198   }
00199   return 0;
00200 }
00201 
00202 class EuslispMessage
00203 {
00204 public:
00205   pointer _message;
00206 
00207   EuslispMessage(pointer message) : _message(message) {
00208   }
00209   EuslispMessage(const EuslispMessage &r) {
00210     context *ctx = current_ctx;
00211     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00212     if ( isclass(r._message) ) {
00213       //ROS_ASSERT(isclass(r._message));
00214       vpush(r._message);
00215       _message = makeobject(r._message);
00216       vpush(_message);
00217       csend(ctx,_message,K_ROSEUS_INIT,0);
00218       vpop();                   // _message
00219       vpop();                   // r._message
00220     } else {
00221       ROS_WARN("r._message must be class");prinx(ctx,r._message,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00222       _message = r._message;
00223     }
00224   }
00225   virtual ~EuslispMessage() { }
00226 
00227   virtual void replaceContents (pointer newMessage) {
00228     _message = newMessage;
00229   }
00230 
00231   virtual const string __getDataType() const {
00232     return getString(_message, K_ROSEUS_DATATYPE);
00233   }
00234   virtual const string __getMD5Sum()   const {
00235     return getString(_message, K_ROSEUS_MD5SUM);
00236   }
00237   virtual const string __getMessageDefinition() const {
00238     return getString(_message, K_ROSEUS_DEFINITION);
00239   }
00240   virtual const string __getServiceDataType() const {
00241     return getString(_message, K_ROSEUS_DATATYPE);
00242   }
00243   virtual const string __getServerMD5Sum()    const {
00244     return getString(_message, K_ROSEUS_MD5SUM);
00245   }
00246 
00247   uint32_t serializationLength() const {
00248     context *ctx = current_ctx;
00249     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00250     pointer a,curclass;
00251     a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(_message),&curclass);
00252     ROS_ASSERT(a!=NIL);
00253     return getInteger(_message, K_ROSEUS_SERIALIZATION_LENGTH);
00254   }
00255 
00256   virtual uint8_t *serialize(uint8_t *writePtr, uint32_t seqid) const
00257   {
00258     context *ctx = current_ctx;
00259     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00260     pointer a,curclass;
00261     vpush(_message);            // to avoid GC
00262     uint32_t len = serializationLength();
00263     vpop();                     // pop _message
00264     a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZE,classof(_message),&curclass);
00265     ROS_ASSERT(a!=NIL);
00266     pointer r = csend(ctx,_message,K_ROSEUS_SERIALIZE,0);
00267     ROS_ASSERT(isstring(r));
00268     memcpy(writePtr, get_string(r), len);
00269     //ROS_INFO("serialize");
00270 
00271     return writePtr + len;
00272   }
00273 
00274   virtual uint8_t *deserialize(uint8_t *readPtr, uint32_t sz)
00275   {
00276     context *ctx = current_ctx;
00277     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00278     pointer a,curclass;
00279 
00280     if ( sz == 0 ) {
00281       ROS_DEBUG("empty message!");
00282       return readPtr;
00283     }
00284     vpush(_message);
00285     a = (pointer)findmethod(ctx,K_ROSEUS_DESERIALIZE,classof(_message),&curclass);
00286     ROS_ASSERT(a!=NIL);
00287     pointer p = makestring((char *)readPtr, sz);
00288     pointer r;
00289     r = csend(ctx,_message,K_ROSEUS_DESERIALIZE,1,p);
00290     ROS_ASSERT(r!=NIL);
00291     //ROS_INFO("deserialize %d", __serialized_length);
00292     vpop(); // pop _message
00293 
00294     return readPtr + sz;
00295   }
00296 };
00297 
00298 namespace ros{
00299   namespace serialization{
00300 template<> struct Serializer<EuslispMessage> {
00301   template<typename Stream>
00302   inline static void write(Stream& stream, boost::call_traits<EuslispMessage>::param_type t) {
00303     t.serialize(stream.getData(), 0);
00304   }
00305 
00306   template<typename Stream>
00307   inline static void read(Stream& stream, boost::call_traits<EuslispMessage>::reference t) {
00308     t.deserialize(stream.getData(), stream.getLength());
00309   }
00310   inline static uint32_t serializedLength(boost::call_traits<EuslispMessage>::param_type t) {
00311     return t.serializationLength();
00312   }
00313 };
00314   }
00315 }
00316 
00317 /************************************************************
00318  *   Subscriptions
00319  ************************************************************/
00320 class EuslispSubscriptionCallbackHelper : public ros::SubscriptionCallbackHelper {
00321 public:
00322   pointer _scb,_args;
00323   EuslispMessage _msg;
00324 
00325   EuslispSubscriptionCallbackHelper(pointer scb, pointer args,pointer tmpl) :  _args(args), _msg(tmpl) {
00326     context *ctx = current_ctx;
00327     mutex_trylock(&mark_lock);
00328     //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00329     //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00330     if (piscode(scb)) { // compiled code
00331       _scb=scb;
00332     } else if ((ccar(scb))==LAMCLOSURE) { // uncompiled code
00333       if ( ccar(ccdr(scb)) != NIL ) { // function
00334         _scb=ccar(ccdr(scb));
00335       } else { // lambda function
00336         _scb=scb;
00337       }
00338     } else {
00339       ROS_ERROR("subscription callback function install error");
00340     }
00341     // avoid gc
00342     pointer p=gensym(ctx);
00343     setval(ctx,intern(ctx,(char*)(p->c.sym.pname->c.str.chars),strlen((char*)(p->c.sym.pname->c.str.chars)),lisppkg),cons(ctx,scb,args));
00344     mutex_unlock(&mark_lock);
00345   }
00346   ~EuslispSubscriptionCallbackHelper() {
00347       ROS_ERROR("subscription gc");
00348   }
00349   virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams& param) {
00350 #if DEBUG
00351     cerr << __PRETTY_FUNCTION__ << endl;
00352     cerr << "param.length = " << param.length << endl;
00353     cerr << "param.buffer = " << (param.buffer + 4) << endl;
00354     cerr << "c_header == " << param.connection_header << endl;
00355 #endif
00356     ros::VoidConstPtr ptr(new EuslispMessage(_msg));
00357     EuslispMessage *eus_msg = (EuslispMessage *)(ptr.get());
00358     eus_msg->deserialize(param.buffer, param.length);
00359 
00360     return ptr;
00361   }
00362   virtual void call(ros::SubscriptionCallbackHelperCallParams& param) {
00363     EuslispMessage* eus_msg = (EuslispMessage *)((void *)param.event.getConstMessage().get());
00364     context *ctx = current_ctx;
00365     pointer argp=_args;
00366     int argc=0;
00367     //ROS_WARN("func");prinx(ctx,_scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00368     //ROS_WARN("argc");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00369     vpush(eus_msg->_message);    // to avoid GC
00370     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
00371       ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
00372     }
00373     
00374     while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
00375     vpush((pointer)(eus_msg->_message));argc++;
00376     
00377     ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
00378     while(argc-->0)vpop();
00379     vpop();    // remove eus_msg._message
00380   }
00381   virtual const std::type_info& getTypeInfo() {
00382     return typeid(EuslispMessage);
00383   }
00384   virtual bool isConst(){
00385     return true;
00386   }
00387   virtual bool hasHeader(){
00388     return true;
00389   }
00390 };
00391 
00392 /************************************************************
00393  *   ServiceCall
00394  ************************************************************/
00395 class EuslispServiceCallbackHelper : public ros::ServiceCallbackHelper {
00396 public:
00397   pointer _scb, _args;
00398   EuslispMessage _req, _res;
00399   string md5, datatype, requestDataType, responseDataType,
00400     requestMessageDefinition, responseMessageDefinition;
00401 
00402   EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass) : _args(args), _req(reqclass), _res(resclass), md5(smd5), datatype(sdatatype) {
00403     context *ctx = current_ctx;
00404     mutex_trylock(&mark_lock);
00405     //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00406     //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00407 
00408     if (piscode(scb)) { // compiled code
00409       _scb=scb;
00410     } else if ((ccar(scb))==LAMCLOSURE) {
00411       if ( ccar(ccdr(scb)) != NIL ) { // function
00412         _scb=ccar(ccdr(scb));
00413       } else { // lambda function
00414         _scb=scb;
00415       }
00416     } else  {
00417       ROS_ERROR("service callback function install error");
00418     }
00419     // avoid gc
00420     pointer p=gensym(ctx);
00421     setval(ctx,intern(ctx,(char*)(p->c.sym.pname->c.str.chars),strlen((char*)(p->c.sym.pname->c.str.chars)),lisppkg),cons(ctx,scb,args));
00422 
00423     requestDataType = _req.__getDataType();
00424     responseDataType = _res.__getDataType();
00425     requestMessageDefinition = _req.__getMessageDefinition();
00426     responseMessageDefinition = _res.__getMessageDefinition();
00427     mutex_unlock(&mark_lock);
00428   }
00429   ~EuslispServiceCallbackHelper() { }
00430 
00431   virtual boost::shared_ptr<EuslispMessage> createRequest() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_req)); }
00432   virtual boost::shared_ptr<EuslispMessage> createResponse() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_res)); }
00433 
00434   virtual std::string getMD5Sum() { return md5; }
00435   virtual std::string getDataType() { return datatype; }
00436   virtual std::string getRequestDataType() { return requestDataType; }
00437   virtual std::string getResponseDataType() { return responseDataType; }
00438   virtual std::string getRequestMessageDefinition() { return requestMessageDefinition; }
00439   virtual std::string getResponseMessageDefinition() { return responseMessageDefinition; }
00440 
00441   virtual bool call(ros::ServiceCallbackHelperCallParams& params) {
00442     context *ctx = current_ctx;
00443     pointer r, argp=_args;
00444     int argc=0;
00445 
00446     vpush(_res._message);       // _res._message
00447     vpush(_req._message);       // _res._message, _req._message
00448 
00449     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
00450       ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
00451     }
00452     // Deserialization
00453     EuslispMessage eus_msg(_req);
00454     vpush(eus_msg._message);    // _res._message, _req._message, eus_msg._message
00455     eus_msg.deserialize(params.request.message_start, params.request.num_bytes);
00456 
00457     while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
00458     vpush((pointer) eus_msg._message);argc++;
00459 
00460     r = ufuncall(ctx, (ctx->callfp?ctx->callfp->form:NIL),
00461                  _scb, (pointer)(ctx->vsp-argc),
00462                  NULL, argc);
00463     while(argc-->0)vpop();// _res._message, _req._message, eus_msg._message
00464     vpush(r); // _res._message, _req._message, eus_msg._message, r, 
00465     // Serializaion
00466     EuslispMessage eus_res(_res);
00467     eus_res.replaceContents(r);
00468     // check return value is valid
00469     pointer ret_serialize_method, ret_class;
00470     if (ispointer(r)) {
00471       ret_serialize_method = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(r),&ret_class); }
00472     if (!ispointer(r) || ret_serialize_method == NIL) {
00473       ROS_ERROR("you may not return valid value in service callback");
00474       vpop(); // _res._message, _req._message, eus_msg._message, r
00475       vpop(); // _res._message, _req._message, eus_msg._message
00476       vpop(); // _res._message, _req._message,
00477       vpop(); // _res._message
00478       return false;
00479     }
00480     vpush(eus_res._message);    // _res._message, _req._message, eus_msg._message, r, eus_res._message
00481     uint32_t serialized_length = eus_res.serializationLength();
00482     params.response.num_bytes = serialized_length + 5; // add 5 bytes of message header
00483     params.response.buf.reset (new uint8_t[params.response.num_bytes]);
00484     params.response.message_start = 0;
00485 
00486     // SerializedResponseMessage
00487     uint8_t *tmp = params.response.buf.get();
00488     *tmp++ = 1; // 1 byte of success services flag, now always set true
00489     *tmp++ = (uint8_t)((serialized_length >> 0) & 0xFF); // 4bytes of message length
00490     *tmp++ = (uint8_t)((serialized_length >> 8) & 0xFF);
00491     *tmp++ = (uint8_t)((serialized_length >> 16) & 0xFF);
00492     *tmp++ = (uint8_t)((serialized_length >> 24) & 0xFF);
00493     eus_res.serialize(tmp, 0);
00494 #if DEBUG
00495     cerr << "num bytes = " << params.response.num_bytes << endl;
00496     ROS_INFO("message_start =  %X",params.response.message_start);
00497     ROS_INFO("message_ptr =  %X",params.response.buf.get());
00498     tmp = params.response.buf.get();
00499     for(int i=0;i<params.response.num_bytes;i++){
00500       ROS_INFO("%X", tmp[i]);
00501     }
00502 #endif
00503     vpop(); // _res._message, _req._message, eus_msg._message, r, eus_res._message
00504     vpop(); // _res._message, _req._message, eus_msg._message, r
00505     vpop(); // _res._message, _req._message, eus_msg._message
00506     vpop(); // _res._message, _req._message,
00507     vpop(); // _res._message
00508     return true;
00509   }
00510 };
00511 
00512 void roseusSignalHandler(int sig)
00513 {
00514     // memoize for euslisp handler...
00515     context *ctx=euscontexts[thr_self()];
00516     ctx->intsig = sig;
00517 }
00518 
00519 /************************************************************
00520  *   EUSLISP functions
00521  ************************************************************/
00522 pointer ROSEUS(register context *ctx,int n,pointer *argv)
00523 {
00524   char name[256] = "";
00525   uint32_t options = 0;
00526   int cargc = 0;
00527   char *cargv[32];
00528 
00529   if( s_bInstalled ) {
00530     ROS_WARN("ROSEUS is already installed as %s", ros::this_node::getName().c_str());
00531     return (T);
00532   }
00533 
00534   ckarg(3);
00535   if (isstring(argv[0]))
00536     strncpy(name,(char *)(argv[0]->c.str.chars),255);
00537   else error(E_NOSTRING);
00538   options = ckintval(argv[1]);
00539   pointer p = argv[2];
00540   if (islist(p)) {
00541     while (1) {
00542       if (!iscons(p)) break;
00543       cargv[cargc]=(char *)((ccar(p))->c.str.chars);
00544       cargc++;
00545       p=ccdr(p);
00546     }
00547   } else error(E_NOSEQ);
00548 
00549   for (unsigned int i=0; i < strlen(name); i++)
00550     if ( ! isalpha(name[i]) ) name[i] = '_';
00551 
00552   K_ROSEUS_MD5SUM   = defkeyword(ctx,"MD5SUM-");
00553   K_ROSEUS_DATATYPE = defkeyword(ctx,"DATATYPE-");
00554   K_ROSEUS_DEFINITION = defkeyword(ctx,"DEFINITION-");
00555   K_ROSEUS_SERIALIZATION_LENGTH = defkeyword(ctx,"SERIALIZATION-LENGTH");
00556   K_ROSEUS_SERIALIZE   = defkeyword(ctx,"SERIALIZE");
00557   K_ROSEUS_DESERIALIZE = defkeyword(ctx,"DESERIALIZE");
00558   K_ROSEUS_GET  = defkeyword(ctx,"GET");
00559   K_ROSEUS_INIT = defkeyword(ctx,"INIT");
00560   K_ROSEUS_REQUEST  = defkeyword(ctx,"REQUEST");
00561   K_ROSEUS_RESPONSE = defkeyword(ctx,"RESPONSE");
00562   K_ROSEUS_GROUPNAME = defkeyword(ctx,"GROUPNAME");
00563   K_ROSEUS_ONESHOT = defkeyword(ctx,"ONESHOT");
00564   K_ROSEUS_LAST_EXPECTED = defkeyword(ctx,"LAST-EXPECTED");
00565   K_ROSEUS_LAST_REAL = defkeyword(ctx,"LAST-REAL");
00566   K_ROSEUS_CURRENT_EXPECTED = defkeyword(ctx,"CURRENT-EXPECTED");
00567   K_ROSEUS_CURRENT_REAL = defkeyword(ctx,"CURRENT-REAL");
00568   K_ROSEUS_LAST_DURATION = defkeyword(ctx,"LAST-DURATION");
00569   K_ROSEUS_SEC = defkeyword(ctx,"SEC");
00570   K_ROSEUS_NSEC = defkeyword(ctx,"NSEC");
00571 
00572   s_mapAdvertised.clear();
00573   s_mapSubscribed.clear();
00574   s_mapServiced.clear();
00575   s_mapTimered.clear();
00576   s_mapHandle.clear();
00577   
00578   /*
00579     force to flag ros::init_options::NoSigintHandler.
00580     In fact, this code make no sence, because we steals
00581     SIGINT handler by the following `signal'.
00582    */
00583   options |= ros::init_options::NoSigintHandler;
00584 
00585   /*
00586     clear ros::master::g_uri which is defined in ros::master::init in __roseus.
00587     this occurs if user set unix::setenv("ROS_MASTER_URI") between __roseus and
00588     ROSEUS.
00589    */
00590   if (!ros::master::g_uri.empty()) {
00591     if ( ros::master::g_uri != getenv("ROS_MASTER_URI") ) {
00592       ROS_WARN("ROS master uri will be changed!!, master uri %s, which is defineed previously is differ from current ROS_MASTE_URI(%s)", ros::master::g_uri.c_str(), getenv("ROS_MASTER_URI"));
00593       ros::master::g_uri.clear();
00594     }
00595   }
00596   try {
00597     ros::init(cargc, cargv, name, options);
00598   } catch (const ros::InvalidNameException &e) {
00599     ROS_ERROR("%s",e.what());
00600     error(E_MISMATCHARG);
00601     return(NIL);
00602   }
00603 
00604   s_node.reset(new ros::NodeHandle());
00605   s_rate = new ros::Rate(50);
00606 
00607   s_bInstalled = true;
00608 
00609   // install signal handler for sigint. DO NOT call unix:signal after
00610   // ros::roseus
00611   signal(SIGINT, roseusSignalHandler);
00612   return (T);
00613 }
00614 
00615 pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx,int n,pointer *argv)
00616 {
00617   isInstalledCheck;
00618   string groupname;
00619   string ns;
00620 
00621   ckarg2(1, 2);
00622   // ;; arguments ;;
00623   // groupname [ namespace ]
00624 
00625   if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
00626   else error(E_NOSTRING);
00627   if ( n > 1 ) {
00628     if(isstring(argv[1])) ns.assign((char *)get_string(argv[1]));
00629     else error(E_NOSTRING);
00630   }
00631 
00632   if( s_mapHandle.find(groupname) != s_mapHandle.end() ) {
00633     ROS_DEBUG("groupname %s is already used", groupname.c_str());
00634     return (NIL);
00635   }
00636 
00637   boost::shared_ptr<NodeHandle> hd;
00638   if ( n > 1 ) {
00639     hd = boost::shared_ptr<NodeHandle> (new NodeHandle(ns));
00640     s_mapHandle[groupname] = hd;
00641   } else {
00642     hd = boost::shared_ptr<NodeHandle>(new NodeHandle());
00643     s_mapHandle[groupname] = hd;
00644   }
00645   //add callbackqueue to hd
00646   hd->setCallbackQueue( new CallbackQueue() );
00647 
00648   return (T);
00649 }
00650 
00651 pointer ROSEUS_SPIN(register context *ctx,int n,pointer *argv)
00652 {
00653   isInstalledCheck;
00654   while (ctx->intsig==0 && ros::ok()) {
00655     ros::spinOnce();
00656     s_rate->sleep();
00657   }
00658   return (NIL);
00659 }
00660 
00661 pointer ROSEUS_SPINONCE(register context *ctx,int n,pointer *argv)
00662 {
00663   isInstalledCheck;
00664   ckarg2(0, 1);
00665   // ;; arguments ;;
00666   // [ groupname ]
00667 
00668   if ( n > 0 ) {
00669     string groupname;
00670     if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
00671     else error(E_NOSTRING);
00672 
00673     map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
00674     if( it == s_mapHandle.end() ) {
00675       ROS_ERROR("Groupname %s is missing", groupname.c_str());
00676       return (T);
00677     }
00678     boost::shared_ptr<NodeHandle > hdl = (it->second);
00679     // spin this nodehandle
00680     ((CallbackQueue *)hdl->getCallbackQueue())->callAvailable();
00681 
00682     return (NIL);
00683   } else {
00684     ros::spinOnce();
00685     return (NIL);
00686   }
00687 }
00688 
00689 pointer ROSEUS_TIME_NOW(register context *ctx,int n,pointer *argv)
00690 {
00691   isInstalledCheck;
00692   pointer timevec;
00693   ros::Time t = ros::Time::now();
00694 
00695   timevec=makevector(C_INTVECTOR,2);
00696   vpush(timevec);
00697   timevec->c.ivec.iv[0]=t.sec;
00698   timevec->c.ivec.iv[1]=t.nsec;
00699   vpop();
00700   return (timevec);
00701 }
00702 
00703 pointer ROSEUS_RATE(register context *ctx,int n,pointer *argv)
00704 {
00705   isInstalledCheck;
00706   numunion nu;
00707   ckarg(1);
00708   float timeout=ckfltval(argv[0]);
00709   s_rate = new ros::Rate(timeout);
00710   return(T);
00711 }
00712 
00713 pointer ROSEUS_SLEEP(register context *ctx,int n,pointer *argv)
00714 {
00715   isInstalledCheck;
00716   s_rate->sleep();
00717   return (T);
00718 }
00719 
00720 pointer ROSEUS_OK(register context *ctx,int n,pointer *argv)
00721 {
00722   if (ros::ok()) {
00723     return (T);
00724   } else {
00725     return (NIL);
00726   }
00727 }
00728 
00729 
00730 #define def_rosconsole_formatter(funcname, rosfuncname)         \
00731   pointer funcname(register context *ctx,int n,pointer *argv)   \
00732   { pointer *argv2,msg;                                         \
00733     int argc2;                                                  \
00734     argc2 = n+1;                                                \
00735     argv2 = (pointer *)malloc(sizeof(pointer)*argc2);           \
00736     argv2[0] = NIL;                                             \
00737     for(int i=0;i<n;i++) argv2[i+1]=argv[i] ;                   \
00738     msg = XFORMAT(ctx, argc2, argv2);                           \
00739     rosfuncname("%s", msg->c.str.chars);                        \
00740     free(argv2);                                                \
00741     return (T);                                                 \
00742   }
00743 
00744 def_rosconsole_formatter(ROSEUS_ROSDEBUG, ROS_DEBUG)
00745 def_rosconsole_formatter(ROSEUS_ROSINFO,  ROS_INFO)
00746 def_rosconsole_formatter(ROSEUS_ROSWARN,  ROS_WARN)
00747 def_rosconsole_formatter(ROSEUS_ROSERROR, ROS_ERROR)
00748 def_rosconsole_formatter(ROSEUS_ROSFATAL, ROS_FATAL)
00749 
00750 pointer ROSEUS_EXIT(register context *ctx,int n,pointer *argv)
00751 {
00752   ROS_INFO("%s", __PRETTY_FUNCTION__);
00753   if( s_bInstalled ) {
00754     ROS_INFO("exiting roseus %ld", (n==0)?n:ckintval(argv[0]));
00755     s_mapAdvertised.clear();
00756     s_mapSubscribed.clear();
00757     s_mapServiced.clear();
00758     s_mapTimered.clear();
00759     s_mapHandle.clear();
00760     ros::shutdown();
00761   }
00762   if (n==0) _exit(0);
00763   else _exit(ckintval(argv[0]));
00764 }
00765 
00766 /************************************************************
00767  *   ROSEUS Publisher/Subscriber
00768  ************************************************************/
00769 pointer ROSEUS_SUBSCRIBE(register context *ctx,int n,pointer *argv)
00770 {
00771   isInstalledCheck;
00772   string topicname;
00773   pointer message, fncallback, args;
00774   int queuesize = 1;
00775   NodeHandle *lnode = s_node.get();
00776 
00777   // ;; arguments ;;
00778   // topicname message_type callbackfunc args0 ... argsN [ queuesize ] [ :groupname groupname ]
00779   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00780   else error(E_NOSTRING);
00781 
00782   if (n > 1 && issymbol(argv[n-2]) && isstring(argv[n-1])) {
00783     if (argv[n-2] == K_ROSEUS_GROUPNAME) {
00784       string groupname;
00785       groupname.assign((char *)get_string(argv[n-1]));
00786       map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
00787       if( it != s_mapHandle.end() ) {
00788         ROS_DEBUG("subscribe with groupname=%s", groupname.c_str());
00789         lnode = (it->second).get();
00790       } else {
00791         ROS_ERROR("Groupname %s is missing. Topic %s is not subscribed. Call (ros::create-nodehandle \"%s\") first.",
00792                   groupname.c_str(), topicname.c_str(), groupname.c_str());
00793         return (NIL);
00794       }
00795       n -= 2;
00796     }
00797   }
00798   if (isint(argv[n-1])) {queuesize = ckintval(argv[n-1]);n--;}
00799   ROS_DEBUG("subscribe %s queuesize=%d", topicname.c_str(), queuesize);
00800   // TODO:need error checking
00801   message = argv[1];
00802   fncallback = argv[2];
00803   args=NIL;
00804   for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
00805 
00806   EuslispMessage msg(message);
00807    boost::shared_ptr<SubscriptionCallbackHelper> *callback =
00808      (new boost::shared_ptr<SubscriptionCallbackHelper>
00809       (new EuslispSubscriptionCallbackHelper(fncallback, args, message)));
00810   SubscribeOptions so(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType());
00811   so.helper = *callback;
00812   Subscriber subscriber = lnode->subscribe(so);
00813   boost::shared_ptr<Subscriber> sub = boost::shared_ptr<Subscriber>(new Subscriber(subscriber));
00814   if ( !!sub ) {
00815     s_mapSubscribed[topicname] = sub;
00816   } else {
00817     ROS_ERROR("s_mapSubscribed");
00818   }
00819 
00820   return (T);
00821 }
00822 
00823 pointer ROSEUS_UNSUBSCRIBE(register context *ctx,int n,pointer *argv)
00824 {
00825   string topicname;
00826 
00827   ckarg(1);
00828   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00829   else error(E_NOSTRING);
00830 
00831   bool bSuccess = s_mapSubscribed.erase(topicname)>0;
00832 
00833   return (bSuccess?T:NIL);
00834 }
00835 
00836 pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx,int n,pointer *argv)
00837 {
00838   string topicname;
00839   int ret;
00840 
00841   ckarg(1);
00842   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00843   else error(E_NOSTRING);
00844 
00845   bool bSuccess = false;
00846   map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
00847   if( it != s_mapSubscribed.end() ) {
00848     boost::shared_ptr<Subscriber> subscriber = (it->second);
00849     ret = subscriber->getNumPublishers();
00850     bSuccess = true;
00851   }
00852 
00853   return (bSuccess?(makeint(ret)):NIL);
00854 }
00855 
00856 pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx,int n,pointer *argv)
00857 {
00858   string topicname;
00859   string ret;
00860 
00861   ckarg(1);
00862   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00863   else error(E_NOSTRING);
00864 
00865   bool bSuccess = false;
00866   map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
00867   if( it != s_mapSubscribed.end() ) {
00868     boost::shared_ptr<Subscriber> subscriber = (it->second);
00869     ret = subscriber->getTopic();
00870     bSuccess = true;
00871   }
00872 
00873   return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
00874 }
00875 
00876 pointer ROSEUS_ADVERTISE(register context *ctx,int n,pointer *argv)
00877 {
00878   isInstalledCheck;
00879   string topicname;
00880   pointer message;
00881   int queuesize = 1;
00882   bool latch = false;
00883 
00884   ckarg2(2,4);
00885   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00886   else error(E_NOSTRING);
00887 
00888   message = argv[1];
00889   if ( n > 2 ) {
00890     queuesize = ckintval(argv[2]);
00891   }
00892   if ( n > 3 ) {
00893     latch = (argv[3]!=NIL ? true : false);
00894   }
00895   ROS_DEBUG("advertise %s %d %d", topicname.c_str(), queuesize, latch);
00896   if( s_mapAdvertised.find(topicname) != s_mapAdvertised.end() ) {
00897     ROS_WARN("topic %s already advertised", topicname.c_str());
00898     return (NIL);
00899   }
00900 
00901   EuslispMessage msg(message);
00902   AdvertiseOptions ao(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType(), msg.__getMessageDefinition());
00903   ao.latch = latch;
00904   Publisher publisher = s_node->advertise(ao);
00905   boost::shared_ptr<Publisher> pub = boost::shared_ptr<Publisher>(new Publisher(publisher));
00906   if ( !!pub ) {
00907     s_mapAdvertised[topicname] = pub;
00908   } else {
00909     ROS_ERROR("s_mapAdvertised");
00910   }
00911 
00912   return (T);
00913 }
00914 
00915 pointer ROSEUS_UNADVERTISE(register context *ctx,int n,pointer *argv)
00916 {
00917   string topicname;
00918 
00919   ckarg(1);
00920   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00921   else error(E_NOSTRING);
00922 
00923   bool bSuccess = s_mapAdvertised.erase(topicname)>0;
00924 
00925   return (bSuccess?T:NIL);
00926 }
00927 
00928 pointer ROSEUS_PUBLISH(register context *ctx,int n,pointer *argv)
00929 {
00930   isInstalledCheck;
00931   string topicname;
00932   pointer emessage;
00933 
00934   ckarg(2);
00935   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00936   else error(E_NOSTRING);
00937 
00938   emessage = argv[1];
00939 
00940   bool bSuccess = false;
00941   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00942   if( it != s_mapAdvertised.end() ) {
00943     boost::shared_ptr<Publisher> publisher = (it->second);
00944     EuslispMessage message(emessage);
00945     publisher->publish(message);
00946     bSuccess = true;
00947   }
00948 
00949   if ( ! bSuccess ) {
00950     ROS_ERROR("attempted to publish to topic %s, which was not " \
00951               "previously advertised. call (ros::advertise \"%s\") first.",
00952               topicname.c_str(), topicname.c_str());
00953   }
00954 
00955   return (T);
00956 }
00957 
00958 pointer ROSEUS_GETNUMSUBSCRIBERS(register context *ctx,int n,pointer *argv)
00959 {
00960   string topicname;
00961   int ret;
00962 
00963   ckarg(1);
00964   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00965   else error(E_NOSTRING);
00966 
00967   bool bSuccess = false;
00968   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00969   if( it != s_mapAdvertised.end() ) {
00970     boost::shared_ptr<Publisher> publisher = (it->second);
00971     ret = publisher->getNumSubscribers();
00972     bSuccess = true;
00973   }
00974 
00975   if ( ! bSuccess ) {
00976     ROS_ERROR("attempted to getNumSubscribers to topic %s, which was not " \
00977               "previously advertised. call (ros::advertise \"%s\") first.",
00978               topicname.c_str(), topicname.c_str());
00979   }
00980 
00981   return (bSuccess?(makeint(ret)):NIL);
00982 }
00983 
00984 pointer ROSEUS_GETTOPICPUBLISHER(register context *ctx,int n,pointer *argv)
00985 {
00986   string topicname;
00987   string ret;
00988 
00989   ckarg(1);
00990   if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
00991   else error(E_NOSTRING);
00992 
00993   bool bSuccess = false;
00994   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00995   if( it != s_mapAdvertised.end() ) {
00996     boost::shared_ptr<Publisher> publisher = (it->second);
00997     ret = publisher->getTopic();
00998     bSuccess = true;
00999   }
01000 
01001   return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
01002 }
01003 
01004 /************************************************************
01005  *   ROSEUS ServiceCall
01006  ************************************************************/
01007 pointer ROSEUS_WAIT_FOR_SERVICE(register context *ctx,int n,pointer *argv)
01008 {
01009   isInstalledCheck;
01010   string service;
01011 
01012   ckarg2(1,2);
01013   if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
01014   else error(E_NOSTRING);
01015 
01016   int32_t timeout = -1;
01017 
01018   if( n > 1 )
01019     timeout = (int32_t)ckintval(argv[1]);
01020 
01021   bool bSuccess = service::waitForService(service, ros::Duration(timeout));
01022 
01023   return (bSuccess?T:NIL);
01024 }
01025 
01026 pointer ROSEUS_SERVICE_EXISTS(register context *ctx,int n,pointer *argv)
01027 {
01028   isInstalledCheck;
01029   string service;
01030 
01031   ckarg(1);
01032   if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
01033   else error(E_NOSTRING);
01034 
01035   bool bSuccess = service::exists(service, true);
01036 
01037   return (bSuccess?T:NIL);
01038 }
01039 
01040 pointer ROSEUS_SERVICE_CALL(register context *ctx,int n,pointer *argv)
01041 {
01042   isInstalledCheck;
01043   string service;
01044   pointer emessage;
01045   bool persist = false;
01046   ckarg2(2,3);
01047   if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
01048   else  error(E_NOSTRING);
01049   emessage = argv[1];
01050   if ( n > 2 ) {
01051       persist = (argv[2] != NIL ? true : false);
01052   }
01053   static std::map<std::string, ros::ServiceClient> service_cache;
01054   ServiceClient client;
01055   EuslispMessage request(emessage);
01056   vpush(request._message);      // to avoid GC, it may not be required...
01057   EuslispMessage response(csend(ctx,emessage,K_ROSEUS_RESPONSE,0));
01058   vpush(response._message);     // to avoid GC, its important
01059   if (persist == false) {
01060     ServiceClientOptions sco(service, request.__getMD5Sum(), false, M_string());
01061     client = s_node->serviceClient(sco);
01062   }
01063   else {
01064     // check the instance of client
01065     
01066     if (service_cache.find(service) != service_cache.end()) {
01067       client = service_cache[service];
01068     }
01069     else {
01070       ServiceClientOptions sco(service, request.__getMD5Sum(), true, M_string());
01071       client = s_node->serviceClient(sco);
01072       service_cache[service] = client;
01073     }
01074   }
01075     // NEED FIX
01076   bool bSuccess =  client.call(request, response, request.__getMD5Sum());
01077   vpop();                       // pop response._message
01078   vpop();                       // pop request._message
01079   if ( ! bSuccess ) {
01080     ROS_ERROR("attempted to call service  %s, but failed ",
01081               ros::names::resolve(service).c_str());
01082     if (persist) {
01083       // cleanup service_cache
01084       service_cache.erase(service_cache.find(service));
01085     }
01086   }
01087 
01088   return (response._message);
01089 }
01090 
01091 pointer ROSEUS_ADVERTISE_SERVICE(register context *ctx,int n,pointer *argv)
01092 {
01093   isInstalledCheck;
01094   string service;
01095   pointer emessage;
01096   pointer fncallback, args;
01097 
01098   if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
01099   else error(E_NOSTRING);
01100   emessage = argv[1];
01101   fncallback = argv[2];
01102   args=NIL;
01103   for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
01104   if( s_mapServiced.find(service) != s_mapServiced.end() ) {
01105     ROS_INFO("service %s already advertised", service.c_str());
01106     return (NIL);
01107   }
01108 
01109   EuslispMessage message(emessage);
01110   vpush(message._message);      // to avoid GC in csend
01111   pointer request(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_REQUEST));
01112   pointer response(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_RESPONSE));
01113   vpop();                       // pop message._message
01114   boost::shared_ptr<EuslispServiceCallbackHelper> *callback =
01115     (new boost::shared_ptr<EuslispServiceCallbackHelper>
01116      (new EuslispServiceCallbackHelper(fncallback, args, message.__getMD5Sum(),
01117                                        message.__getDataType(), request, response)));
01118   AdvertiseServiceOptions aso;
01119   aso.service.assign(service);
01120   aso.datatype = (*callback->get()).getDataType();
01121   aso.md5sum = (*callback->get()).getMD5Sum();
01122   aso.req_datatype = (*callback->get()).getRequestDataType();
01123   aso.res_datatype = (*callback->get()).getResponseDataType();
01124   aso.helper = *callback;
01125   ServiceServer server = s_node->advertiseService(aso);
01126   boost::shared_ptr<ServiceServer> ser = boost::shared_ptr<ServiceServer>(new ServiceServer(server));
01127   if ( !!ser ) {
01128     s_mapServiced[service] = ser;
01129   } else {
01130     ROS_ERROR("s_mapServiced");
01131   }
01132 
01133   return (T);
01134 }
01135 
01136 pointer ROSEUS_UNADVERTISE_SERVICE(register context *ctx,int n,pointer *argv)
01137 {
01138   string service;
01139 
01140   ckarg(1);
01141   if (isstring(argv[0])) service = ros::names::resolve((char *)(argv[0]));
01142   else error(E_NOSTRING);
01143 
01144   ROS_DEBUG("unadvertise %s", service.c_str());
01145   bool bSuccess = s_mapServiced.erase(service)>0;
01146 
01147   return (bSuccess?T:NIL);
01148 }
01149 
01150 void EusValueToXmlRpc(register context *ctx, pointer argp, XmlRpc::XmlRpcValue& rpc_value)
01151 {
01152   numunion nu;
01153 
01154   if ( islist(argp) && islist(ccar(argp))) { // alist
01155     pointer a;
01156     int j;
01157     // set keys
01158     std::ostringstream stringstream;
01159     stringstream << "<value><struct>";
01160     a = argp;
01161     while(islist(a)){
01162       pointer v = ccar(a);
01163       if ( iscons(v) ) { // is alist
01164         if ( issymbol(ccar(v)) ) {
01165           string skey = string((char *)get_string(ccar(v)->c.sym.pname));
01166           boost::algorithm::to_lower(skey);
01167           stringstream << "<member><name>" << skey << "</name><value><boolean>0</boolean></value></member>";
01168         }else{
01169           ROS_ERROR("ROSEUS_SET_PARAM: EusValueToXmlRpc: assuming symbol");prinx(ctx,ccar(v),ERROUT);flushstream(ERROUT);terpri(ERROUT);
01170         }
01171       }else{
01172         ROS_ERROR("ROSEUS_SET_PARAM: EusValueToXmlRpc: assuming alist");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
01173       }
01174       a=ccdr(a);
01175     }
01176     stringstream << "</struct></value>";
01177     j=0; rpc_value.fromXml(stringstream.str(), &j);
01178     // set values
01179     a = argp;
01180     while(islist(a)){
01181       pointer v = ccar(a);
01182       if ( iscons(v) ) {
01183         if ( issymbol(ccar(v)) ) {
01184           string skey = string((char *)get_string(ccar(v)->c.sym.pname));
01185           boost::algorithm::to_lower(skey);
01186           XmlRpc::XmlRpcValue p;
01187           EusValueToXmlRpc(ctx, ccdr(v), p);
01188           rpc_value[skey] = p;
01189         }
01190       }
01191       a=ccdr(a);
01192     }
01193   } else if ( islist(argp) ) { // list
01194     pointer a;
01195     int i;
01196     // get size
01197     a = argp;
01198     i = 0; while ( islist(a) ) { a=ccdr(a); i++; }
01199     rpc_value.setSize(i);
01200     // fill items
01201     a = argp;
01202     i = 0;
01203     while ( islist(a) ) {
01204       XmlRpc::XmlRpcValue p;
01205       EusValueToXmlRpc(ctx, ccar(a), p);
01206       rpc_value[i] = p;
01207       a=ccdr(a);
01208       i++;
01209     }
01210   } else if ( isstring(argp) ) {
01211     rpc_value = (char *)get_string(argp);
01212   } else if ( isint(argp) ) {
01213     rpc_value = (int)(intval(argp));
01214   } else if  ( isflt(argp) ) {
01215     rpc_value = (double)(fltval(argp));
01216   } else if (argp == T) {
01217     rpc_value = XmlRpc::XmlRpcValue((bool)true);
01218   } else if (argp == NIL) {
01219     rpc_value = XmlRpc::XmlRpcValue((bool)false);
01220   } else if ( issymbol(argp) ) {
01221     string s((char *)get_string(argp->c.sym.pname));
01222     boost::algorithm::to_lower(s);
01223     rpc_value = s.c_str();
01224   } else {
01225     ROS_ERROR("EusValueToXmlRpc: unknown parameters");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
01226     error(E_MISMATCHARG);
01227   }
01228 }
01229 
01230 pointer ROSEUS_SET_PARAM(register context *ctx,int n,pointer *argv)
01231 {
01232   string key;
01233   string s;
01234 
01235   ckarg(2);
01236   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01237   else error(E_NOSTRING);
01238   XmlRpc::XmlRpcValue param;
01239   EusValueToXmlRpc(ctx, argv[1], param);
01240   ros::param::set(key,param);
01241 
01242   return (T);
01243 }
01244 
01245 pointer XmlRpcToEusValue(register context *ctx, XmlRpc::XmlRpcValue rpc_value)
01246 {
01247   numunion nu;
01248   pointer ret, first;
01249 
01250   if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeBoolean ){
01251     if ( rpc_value ) return T; else return NIL;
01252   }
01253   else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeDouble ){
01254     return makeflt((double)rpc_value);
01255   }
01256   else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeInt ){
01257     return makeint((int)rpc_value);
01258   }
01259   else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeString ){
01260     std::string str = rpc_value;
01261     return makestring((char*)str.c_str(), ((std::string)rpc_value).length());
01262   }
01263   else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeArray ){
01264     ret = cons(ctx, NIL, NIL);
01265     first = ret;
01266     vpush(ret);
01267     for ( int i = 0; i < rpc_value.size(); i++){
01268       ccdr(ret) = cons(ctx, XmlRpcToEusValue(ctx, rpc_value[i]), NIL);
01269       ret = ccdr(ret);
01270     }
01271     vpop(); // vpush(ret);
01272     return ccdr(first);
01273   }
01274   else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeStruct ){
01275     ret = cons(ctx, NIL, NIL);
01276     first = ret;
01277     vpush(ret);
01278     XmlRpc::XmlRpcValue::iterator it = rpc_value.begin();
01279     while(it !=rpc_value.end()) {
01280       std::string key = it->first;
01281       pointer tmp = cons(ctx, makestring((char*)key.c_str(), key.length()), NIL);
01282       vpush(tmp);
01283       ccdr(tmp) = XmlRpcToEusValue(ctx, it->second);
01284       ccdr(ret) = cons(ctx, tmp, NIL);
01285       ret = ccdr(ret);
01286       vpop(); // vpush(tmp);
01287       it++;
01288     }
01289     vpop(); // vpush(ret);
01290     return ccdr(first);
01291   } else {
01292     ROS_FATAL("unknown rosparam type!");
01293     return NIL;
01294   }
01295   return NIL;
01296 }
01297 
01298 pointer XmlRpcToEusList(register context *ctx, XmlRpc::XmlRpcValue param_list)
01299 {
01300     numunion nu;
01301     pointer ret, first;
01302     ret = cons(ctx, NIL, NIL);
01303     first = ret;
01304     vpush(ret);
01305     if ( param_list.getType() == XmlRpc::XmlRpcValue::TypeArray ){
01306         for ( int i = 0; i < param_list.size(); i++){
01307             if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeBoolean ){
01308                 if ( param_list[i] ){
01309                     ccdr(ret) = cons(ctx, T, NIL);
01310                     ret = ccdr(ret);
01311                 } else {
01312                     ccdr(ret) = cons(ctx, NIL, NIL);
01313                     ret = ccdr(ret);
01314                 }
01315             }
01316             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble ){
01317                 ccdr(ret) = cons(ctx, makeflt((double)param_list[i]), NIL);
01318                 ret = ccdr(ret);
01319             }
01320             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeInt ){
01321                 ccdr(ret) = cons(ctx, makeint((int)param_list[i]), NIL);
01322                 ret = ccdr(ret);
01323             }
01324             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeString ){
01325                 std::string str = param_list[i];
01326                 ccdr(ret) = cons(ctx, makestring((char*)str.c_str(), ((std::string)param_list[i]).length()), NIL);
01327                 ret = ccdr(ret);
01328             }
01329             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct ){
01330                 ccdr(ret) = cons(ctx, XmlRpcToEusValue(ctx, param_list[i]), NIL);
01331                 ret = ccdr(ret);
01332             }
01333             else {
01334                 ROS_FATAL("unknown rosparam type!");
01335                 vpop();         // remove vpush(ret)
01336                 return NIL;
01337             }
01338         }
01339         vpop();                 // remove vpush(ret)
01340         return ccdr(first);
01341     } else if ( param_list.getType() == XmlRpc::XmlRpcValue::TypeStruct ) {
01342         return XmlRpcToEusValue(ctx, param_list);
01343     } else
01344         return (NIL);
01345 }
01346 
01347 pointer ROSEUS_GET_PARAM(register context *ctx,int n,pointer *argv)
01348 {
01349   numunion nu;
01350   string key;
01351 
01352   ckarg2(1,2);
01353   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01354   else error(E_NOSTRING);
01355 
01356   string s;
01357   double d;
01358   bool b;
01359   int i;
01360   pointer ret;
01361   XmlRpc::XmlRpcValue param_list;
01362 
01363   if ( ros::param::get(key, s) ) {
01364     ret = makestring((char *)s.c_str(), s.length());
01365   } else if ( ros::param::get(key, d) ) {
01366     ret = makeflt(d);
01367   } else if ( ros::param::get(key, i) ) {
01368     ret = makeint(i);
01369   } else if ( ros::param::get(key, b) ) {
01370       if ( b == true )
01371           ret = T;
01372       else
01373           ret = NIL;
01374   } else if (ros::param::get(key, param_list)){
01375       ret = XmlRpcToEusList(ctx, param_list);
01376   }else {
01377     if ( n == 2 ) {
01378       ret = COPYOBJ(ctx,1,argv+1);
01379     } else {
01380       ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
01381       ret = NIL;
01382     }
01383   }
01384   return (ret);
01385 }
01386 
01387 pointer ROSEUS_GET_PARAM_CACHED(register context *ctx,int n,pointer *argv)
01388 {
01389   numunion nu;
01390   string key;
01391 
01392   ckarg2(1,2);
01393   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01394   else error(E_NOSTRING);
01395 
01396   string s;
01397   double d;
01398   int i;
01399   bool b;
01400   pointer ret;
01401   XmlRpc::XmlRpcValue param_list;
01402   if ( ros::param::getCached(key, s) ) {
01403     ret = makestring((char *)s.c_str(), s.length());
01404   } else if ( ros::param::getCached(key, d) ) {
01405     ret = makeflt(d);
01406   } else if ( ros::param::getCached(key, i) ) {
01407     ret = makeint(i);
01408   } else if ( ros::param::getCached(key, b) ) {
01409       if ( b == true )
01410           ret = T;
01411       else
01412           ret = NIL;
01413   } else if (ros::param::getCached(key, param_list)){
01414       ret = XmlRpcToEusList(ctx, param_list);
01415   } else {
01416     if ( n == 2 ) {
01417       ret = COPYOBJ(ctx,1,argv+1);
01418     } else {
01419       ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
01420       ret = NIL;
01421     }
01422   }
01423   return (ret);
01424 }
01425 
01426 pointer ROSEUS_HAS_PARAM(register context *ctx,int n,pointer *argv)
01427 {
01428   string key;
01429 
01430   ckarg(1);
01431   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01432   else error(E_NOSTRING);
01433 
01434   return((ros::param::has(key))?(T):(NIL));
01435 }
01436 
01437 pointer ROSEUS_DELETE_PARAM(register context *ctx,int n,pointer *argv)
01438 {
01439   string key;
01440 
01441   ckarg(1);
01442   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01443   else error(E_NOSTRING);
01444 
01445   return((ros::param::del(key))?(T):(NIL));
01446 }
01447 
01448 pointer ROSEUS_ROSPACK_FIND(register context *ctx,int n,pointer *argv)
01449 {
01450   ckarg(1);
01451 
01452   string pkg;
01453   if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
01454   else error(E_NOSTRING);
01455 
01456   try {
01457 #ifdef ROSPACK_EXPORT
01458       rospack::ROSPack rp;
01459       rospack::Package *p = rp.get_pkg(pkg);
01460       if (p!=NULL) return(makestring((char *)p->path.c_str(),p->path.length()));
01461 #else
01462       rospack::Rospack rp;
01463       std::vector<std::string> search_path;
01464       rp.getSearchPathFromEnv(search_path);
01465       rp.crawl(search_path, 1);
01466       std::string path;
01467       if (rp.find(pkg,path)==true) return(makestring((char *)path.c_str(),path.length()));
01468 #endif
01469   } catch (runtime_error &e) {
01470   }
01471   return(NIL);
01472 }
01473 
01474 pointer ROSEUS_ROSPACK_PLUGINS(register context *ctx,int n,pointer *argv)
01475 {
01476   // (ros::rospack-plugins package-name attibute-name)
01477   ckarg(2);
01478   string pkg, attrib;
01479   pointer ret, first;
01480   if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
01481   else error(E_NOSTRING);
01482   if (isstring(argv[1])) attrib.assign((char *)get_string(argv[1]));
01483   else error(E_NOSTRING);
01484   try {
01485       rospack::Rospack rp;
01486       std::vector<std::string> search_path;
01487       rp.getSearchPathFromEnv(search_path);
01488       rp.crawl(search_path, 1);
01489       std::vector<std::string> flags;
01490       if (rp.plugins(pkg, attrib, "", flags)) {
01491           ret = cons(ctx, NIL, NIL);
01492           first = ret;
01493           vpush(ret);
01494           for (size_t i = 0; i < flags.size(); i++) {
01495             // flags[i] = laser_proc /opt/ros/hydro/share/laser_proc/nodelets.xml
01496             std::vector<std::string> parsed_string;
01497             boost::algorithm::split(parsed_string, flags[i], boost::is_any_of(" "));
01498             std::string package = parsed_string[0];
01499             std::string value = parsed_string[1];
01500             pointer tmp = cons(ctx, cons(ctx,
01501                                          makestring((char*)package.c_str(), package.length()),
01502                                          makestring((char*)value.c_str(), value.length())),
01503                                NIL);
01504             ccdr(ret) = tmp;
01505             ret = tmp;
01506           }
01507           vpop();            // ret
01508           return ccdr(first);
01509       }
01510       else {
01511           return(NIL);
01512       }
01513   }
01514   catch (runtime_error &e) {
01515   }
01516   return(NIL);
01517 }
01518 
01519 pointer ROSEUS_RESOLVE_NAME(register context *ctx,int n,pointer *argv)
01520 {
01521   ckarg(1);
01522   if (!isstring(argv[0])) error(E_NOSTRING);
01523   std::string src;
01524   src.assign((char *)(argv[0]->c.str.chars));
01525   std::string dst = ros::names::resolve(src);
01526   return(makestring((char *)dst.c_str(), dst.length()));
01527 }
01528 
01529 pointer ROSEUS_GETNAME(register context *ctx,int n,pointer *argv)
01530 {
01531   ckarg(0);
01532   return(makestring((char *)ros::this_node::getName().c_str(),
01533                     ros::this_node::getName().length()));
01534 }
01535 
01536 pointer ROSEUS_GETNAMESPACE(register context *ctx,int n,pointer *argv)
01537 {
01538   ckarg(0);
01539   // https://github.com/ros/ros_comm/pull/1100
01540   // Clean the namespace to get rid of double or trailing forward slashes
01541   std::string ns  = ros::names::clean(ros::this_node::getNamespace()).c_str();
01542   return(makestring((char *)ns.c_str(), ns.length()));
01543 }
01544 
01545 pointer ROSEUS_SET_LOGGER_LEVEL(register context *ctx, int n, pointer *argv)
01546 {
01547   ckarg(2);
01548   string logger;
01549   if (isstring(argv[0])) logger.assign((char *)get_string(argv[0]));
01550   else error(E_NOSTRING);
01551   int log_level = intval(argv[1]);
01552   ros::console::levels::Level  level = ros::console::levels::Debug;
01553   switch(log_level){
01554   case 1:
01555     level = ros::console::levels::Debug;
01556     break;
01557   case 2:
01558     level = ros::console::levels::Info;
01559     break;
01560   case 3:
01561     level = ros::console::levels::Warn;
01562     break;
01563   case 4:
01564     level = ros::console::levels::Error;
01565     break;
01566   case 5:
01567     level = ros::console::levels::Fatal;
01568     break;
01569   default:
01570     return (NIL);
01571   }
01572 
01573   bool success = ::ros::console::set_logger_level(logger, level);
01574   if (success)
01575     {
01576       console::notifyLoggerLevelsChanged();
01577       return (T);
01578     }
01579   return (NIL);
01580 }
01581 
01582 pointer ROSEUS_GET_HOST(register context *ctx,int n,pointer *argv)
01583 {
01584   ckarg(0);
01585 
01586   std::string host = ros::master::getHost();
01587   return makestring((char*)host.c_str(), host.length());
01588 }
01589 
01590 pointer ROSEUS_GET_NODES(register context *ctx,int n,pointer *argv)
01591 {
01592   ckarg(0);
01593 
01594   ros::V_string nodes;
01595   if ( ! ros::master::getNodes(nodes) ) {
01596     return NIL;
01597   }
01598 
01599   register pointer ret, first;
01600   ret=cons(ctx, NIL, NIL);
01601   first = ret;
01602   vpush(ret);
01603   for (ros::V_string::iterator it = nodes.begin() ; it != nodes.end(); it++) {
01604     std::string node = *it;
01605     ccdr(ret) = cons(ctx, makestring((char *)node.c_str(), node.length()), NIL);
01606     ret = ccdr(ret);
01607   }
01608   vpop(); // vpush(ret)
01609 
01610   return ccdr(first);
01611 }
01612 
01613 pointer ROSEUS_GET_PORT(register context *ctx,int n,pointer *argv)
01614 {
01615   ckarg(0);
01616 
01617   return makeint(ros::master::getPort());
01618 }
01619 
01620 pointer ROSEUS_GET_URI(register context *ctx,int n,pointer *argv)
01621 {
01622   ckarg(0);
01623 
01624   std::string uri = ros::master::getURI();
01625   return makestring((char*)uri.c_str(), uri.length());
01626 }
01627 
01628 pointer ROSEUS_GET_TOPICS(register context *ctx,int n,pointer *argv)
01629 {
01630   ckarg(0);
01631 
01632   ros::master::V_TopicInfo topics;
01633   if ( !ros::master::getTopics(topics) ) {
01634     return NIL;
01635   }
01636 
01637   register pointer ret, first;
01638   ret=cons(ctx, NIL, NIL);
01639   first = ret;
01640   vpush(ret);
01641   for (ros::master::V_TopicInfo::iterator it = topics.begin() ; it != topics.end(); it++) {
01642     const ros::master::TopicInfo& info = *it;
01643     pointer tmp = cons(ctx,makestring((char*)info.name.c_str(), info.name.length()), makestring((char*)info.datatype.c_str(), info.datatype.length()));
01644     vpush(tmp);
01645     ccdr(ret) = cons(ctx, tmp, NIL);
01646     ret = ccdr(ret);
01647     vpop(); // vpush(tmp)
01648   }
01649   vpop(); // vpush(ret)
01650 
01651   return ccdr(first);
01652 }
01653 
01654 class TimerFunction
01655 {
01656   pointer _scb, _args;
01657 public:
01658   TimerFunction(pointer scb, pointer args) : _scb(scb), _args(args) {
01659     //context *ctx = current_ctx;
01660     //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
01661     //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
01662   }
01663   void operator()(const ros::TimerEvent& event)
01664   {
01665     mutex_trylock(&mark_lock);
01666     context *ctx = current_ctx;
01667     pointer argp=_args;
01668     int argc=0;
01669 
01670     pointer clsptr = NIL;
01671     for(int i=0; i<nextcix;i++) {
01672       if(!memcmp(classtab[i].def->c.cls.name->c.sym.pname->c.str.chars,(char *)"TIMER-EVENT",11)) {
01673         clsptr = classtab[i].def;
01674       }
01675     }
01676     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
01677       ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
01678     }
01679 
01680     pointer tevent = makeobject(clsptr);
01681     csend(ctx,tevent,K_ROSEUS_INIT,0);
01682     csend(ctx,tevent,K_ROSEUS_LAST_EXPECTED,2,K_ROSEUS_SEC,makeint(event.last_expected.sec));
01683     csend(ctx,tevent,K_ROSEUS_LAST_EXPECTED,2,K_ROSEUS_NSEC,makeint(event.last_expected.nsec));
01684     csend(ctx,tevent,K_ROSEUS_LAST_REAL,2,K_ROSEUS_SEC,makeint(event.last_real.sec));
01685     csend(ctx,tevent,K_ROSEUS_LAST_REAL,2,K_ROSEUS_NSEC,makeint(event.last_real.nsec));
01686     csend(ctx,tevent,K_ROSEUS_CURRENT_EXPECTED,2,K_ROSEUS_SEC,makeint(event.current_expected.sec));
01687     csend(ctx,tevent,K_ROSEUS_CURRENT_EXPECTED,2,K_ROSEUS_NSEC,makeint(event.current_expected.nsec));
01688     csend(ctx,tevent,K_ROSEUS_CURRENT_REAL,2,K_ROSEUS_SEC,makeint(event.current_real.sec));
01689     csend(ctx,tevent,K_ROSEUS_CURRENT_REAL,2,K_ROSEUS_NSEC,makeint(event.current_real.nsec));
01690     csend(ctx,tevent,K_ROSEUS_LAST_DURATION,2,K_ROSEUS_SEC,makeint(event.profile.last_duration.sec));
01691     csend(ctx,tevent,K_ROSEUS_LAST_DURATION,2,K_ROSEUS_NSEC,makeint(event.profile.last_duration.nsec));
01692 
01693     while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
01694     vpush((pointer)(tevent));argc++;
01695 
01696     ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
01697     while(argc-->0)vpop();
01698 
01699     mutex_unlock(&mark_lock);
01700   }
01701 };
01702 
01703 pointer ROSEUS_CREATE_TIMER(register context *ctx,int n,pointer *argv)
01704 {
01705   isInstalledCheck;
01706   numunion nu;
01707   bool oneshot = false;
01708   pointer fncallback = NIL, args;
01709   NodeHandle *lnode = s_node.get();
01710   string fncallname;
01711   float period=ckfltval(argv[0]);
01712 
01713   mutex_trylock(&mark_lock);
01714   // period callbackfunc args0 ... argsN [ oneshot ]
01715   // ;; oneshot ;;
01716   if (n > 1 && issymbol(argv[n-2]) && issymbol(argv[n-1])) {
01717     if (argv[n-2] == K_ROSEUS_ONESHOT) {
01718       if ( argv[n-1] != NIL ) {
01719         oneshot = true;
01720       }
01721       n -= 2;
01722     }
01723   }
01724   // ;; functions ;;
01725   if (piscode(argv[1])) { // compiled code
01726     fncallback=argv[1];
01727     std::ostringstream stringstream;
01728     stringstream << reinterpret_cast<long>(argv[2]) << " ";
01729     for (int i=3; i<n;i++)
01730       stringstream << string((char*)(argv[i]->c.sym.pname->c.str.chars)) << " ";
01731     fncallname = stringstream.str();
01732   } else if ((ccar(argv[1]))==LAMCLOSURE) { // uncompiled code
01733     if ( ccar(ccdr(argv[1])) != NIL ) { // function
01734       fncallback=ccar(ccdr(argv[1]));
01735       fncallname = string((char*)(fncallback->c.sym.pname->c.str.chars));
01736     } else { // lambda function
01737       fncallback=argv[1];
01738       std::ostringstream stringstream;
01739       stringstream << reinterpret_cast<long>(argv[1]);
01740       fncallname = stringstream.str();
01741     }
01742   } else {
01743     ROS_ERROR("subscription callback function install error");
01744   }
01745 
01746   // ;; arguments ;;
01747   args=NIL;
01748   for (int i=n-1;i>=2;i--) args=cons(ctx,argv[i],args);
01749 
01750   // avoid gc
01751   pointer p=gensym(ctx);
01752   setval(ctx,intern(ctx,(char*)(p->c.sym.pname->c.str.chars),strlen((char*)(p->c.sym.pname->c.str.chars)),lisppkg),cons(ctx,fncallback,args));
01753 
01754   // ;; store mapTimered
01755   ROS_DEBUG("create timer %s at %f (oneshot=%d)", fncallname.c_str(), period, oneshot);
01756   s_mapTimered[fncallname] = lnode->createTimer(ros::Duration(period), TimerFunction(fncallback, args), oneshot);
01757 
01758   mutex_unlock(&mark_lock);
01759   return (T);
01760 }
01761 
01762 /************************************************************
01763  *   __roseus
01764  ************************************************************/
01765 extern pointer K_FUNCTION_DOCUMENTATION;
01766 pointer _defun(context *ctx, char *name, pointer mod, pointer (*f)(), char *doc) {
01767   pointer sym = defun(ctx,name, mod, f);
01768   if(strcmp(doc, "")) {
01769     pointer pdoc = makestring(doc,strlen(doc));
01770     vpush(pdoc); putprop(ctx,sym,pdoc,K_FUNCTION_DOCUMENTATION); vpop();}
01771   return sym;}
01772 
01773 pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
01774 {
01775   pointer rospkg,p=Spevalof(PACKAGE);
01776   rospkg=findpkg(makestring("ROS",3));
01777   if (rospkg == 0) rospkg=makepkg(ctx,makestring("ROS", 3),NIL,NIL);
01778   Spevalof(PACKAGE)=rospkg;
01779 
01780   QANON=defvar(ctx,"*ANONYMOUS-NAME*",makeint(ros::init_options::AnonymousName),rospkg);
01781   QNOOUT=defvar(ctx,"*NO-ROSOUT*",makeint(ros::init_options::NoRosout),rospkg);
01782   QROSDEBUG=defvar(ctx,"*ROSDEBUG*",makeint(1),rospkg);
01783   QROSINFO=defvar(ctx,"*ROSINFO*",makeint(2),rospkg);
01784   QROSWARN=defvar(ctx,"*ROSWARN*",makeint(3),rospkg);
01785   QROSERROR=defvar(ctx,"*ROSERROR*",makeint(4),rospkg);
01786   QROSFATAL=defvar(ctx,"*ROSFATAL*",makeint(5),rospkg);
01787   _defun(ctx,"SPIN",argv[0],(pointer (*)())ROSEUS_SPIN, "Enter simple event loop");
01788 
01789   _defun(ctx,"SPIN-ONCE",argv[0],(pointer (*)())ROSEUS_SPINONCE,
01790          "&optional groupname  ;; spin only group\n\n"
01791          "Process a single round of callbacks.\n");
01792   _defun(ctx,"TIME-NOW-RAW",argv[0],(pointer (*)())ROSEUS_TIME_NOW, "");
01793   _defun(ctx,"RATE",argv[0],(pointer (*)())ROSEUS_RATE, "frequency\n\n" "Construct ros timer for periodic sleeps");
01794   _defun(ctx,"SLEEP",argv[0],(pointer (*)())ROSEUS_SLEEP, "Sleeps for any leftover time in a cycle. Calculated from the last time sleep, reset, or the constructor was called.");
01795   _defun(ctx,"OK",argv[0],(pointer (*)())ROSEUS_OK, "Check whether it's time to exit. ");
01796 
01797   _defun(ctx,"ROS-DEBUG",argv[0],(pointer (*)())ROSEUS_ROSDEBUG,
01798          "write mesage to debug output\n"
01799          "\n"
01800          "      (ros::ros-debug \"this is error ~A\" 0)\n");
01801   _defun(ctx,"ROS-INFO",argv[0],(pointer (*)())ROSEUS_ROSINFO, "write mesage to info output");
01802   _defun(ctx,"ROS-WARN",argv[0],(pointer (*)())ROSEUS_ROSWARN, "write mesage to warn output");
01803   _defun(ctx,"ROS-ERROR",argv[0],(pointer (*)())ROSEUS_ROSERROR, "write mesage to error output");
01804   _defun(ctx,"ROS-FATAL",argv[0],(pointer (*)())ROSEUS_ROSFATAL, "write mesage to fatal output");
01805   _defun(ctx,"EXIT",argv[0],(pointer (*)())ROSEUS_EXIT, "Exit ros clinet");
01806 
01807   _defun(ctx,"SUBSCRIBE",argv[0],(pointer (*)())ROSEUS_SUBSCRIBE,
01808          "topicname message_type callbackfunc args0 ... argsN &optional (queuesize 1) %key (:groupname groupname)\n\n"
01809          "Subscribe to a topic, version for class member function with bare pointer.\n"
01810          "This method connects to the master to register interest in a given topic. The node will automatically be connected with publishers on this topic. On each message receipt, fp is invoked and passed a shared pointer to the message received. This message should not be changed in place, as it is shared with any other subscriptions to this topic.\n"
01811          "\n"
01812          "This version of subscribe is a convenience function for using function, member function, lmabda function:\n"
01813          "      ;; callback function\n"
01814          "      (defun string-cb (msg) (print (list 'cb (sys::thread-self) (send msg :data))))\n"
01815          "      (ros::subscribe \"chatter\" std_msgs::string #'string-cb)\n"
01816          "      ;; lambda function\n"
01817          "      (ros::subscribe \"chatter\" std_msgs::string\n"
01818          "                      #'(lambda (msg) (ros::ros-info\n"
01819          "                                       (format nil \"I heard ~A\" (send msg :data)))))\n"
01820          "      ;; method call\n"
01821          "      (defclass string-cb-class\n"
01822          "        :super propertied-object\n"
01823          "        :slots ())\n"
01824          "      (defmethod string-cb-class\n"
01825          "        (:init () (ros::subscribe \"chatter\" std_msgs::string #'send self :string-cb))\n"
01826          "        (:string-cb (msg) (print (list 'cb self (send msg :data)))))\n"
01827          "      (setq m (instance string-cb-class :init))\n"
01828          );
01829   _defun(ctx,"UNSUBSCRIBE",argv[0],(pointer (*)())ROSEUS_UNSUBSCRIBE, "topicname\n\n""Unsubscribe topic");
01830   _defun(ctx,"GET-NUM-PUBLISHERS",argv[0],(pointer (*)())ROSEUS_GETNUMPUBLISHERS, "Returns the number of publishers this subscriber is connected to. ");
01831   _defun(ctx,"GET-TOPIC-SUBSCRIBER",argv[0],(pointer (*)())ROSEUS_GETTOPICSUBSCRIBER, "topicname\n\n""Retuns the name of topic if it already subscribed");
01832   _defun(ctx,"ADVERTISE",argv[0],(pointer (*)())ROSEUS_ADVERTISE,
01833          "topic message_class &optional (queuesize 1) (latch nil)\n"
01834          "Advertise a topic.\n"
01835          "This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.\n"
01836          "      (ros::advertise \"chatter\" std_msgs::string 1)");
01837   _defun(ctx,"UNADVERTISE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE, "Unadvertise topic");
01838   _defun(ctx,"PUBLISH",argv[0],(pointer (*)())ROSEUS_PUBLISH,
01839          "topic message\n\n"
01840          "Publish a message on the topic\n"
01841          "      (ros::roseus \"talker\")\n"
01842          "      (ros::advertise \"chatter\" std_msgs::string 1)\n"
01843          "      (ros::rate 100)\n"
01844          "      (while (ros::ok)\n"
01845          "        (setq msg (instance std_msgs::string :init))\n"
01846          "        (send msg :data (format nil \"hello world ~a\" (send (ros::time-now) :sec-nsec)))\n"
01847          "        (ros::publish \"chatter\" msg)\n"
01848          "        (ros::sleep))\n");
01849   _defun(ctx,"GET-NUM-SUBSCRIBERS",argv[0],(pointer (*)())ROSEUS_GETNUMSUBSCRIBERS, "Retuns number of subscribers this publish is connected to");
01850   _defun(ctx,"GET-TOPIC-PUBLISHER",argv[0],(pointer (*)())ROSEUS_GETTOPICPUBLISHER, "topicname\n\n""Retuns the name of topic if it already published");
01851 
01852   _defun(ctx,"WAIT-FOR-SERVICE",argv[0],(pointer (*)())ROSEUS_WAIT_FOR_SERVICE, "servicename &optional timeout\n\n""Wait for a service to be advertised and available. Blocks until it is.");
01853   _defun(ctx,"SERVICE-EXISTS", argv[0], (pointer (*)())ROSEUS_SERVICE_EXISTS, "servicename\n\n""Checks if a service is both advertised and available.");
01854   _defun(ctx,"SERVICE-CALL",argv[0],(pointer (*)())ROSEUS_SERVICE_CALL, 
01855          "servicename message_type &optional persist\n\n"
01856          "Invoke RPC service\n"
01857          "      (ros::roseus \"add_two_ints_client\")\n"
01858          "      (ros::wait-for-service \"add_two_ints\")\n"
01859          "      (setq req (instance roseus::AddTwoIntsRequest :init))\n"
01860          "      (send req :a (random 10))\n"
01861          "      (send req :b (random 20))\n"
01862          "      (setq res (ros::service-call \"add_two_ints\" req t))\n"
01863          "      (format t \"~d + ~d = ~d~~%\" (send req :a) (send req :b) (send res :sum))\n");
01864   _defun(ctx,"ADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_ADVERTISE_SERVICE,
01865          "servicename message_type callback function\n\n"
01866          "Advertise a service\n"
01867          "      (ros::advertise-service \"add_two_ints\" roseus::AddTwoInts #'add-two-ints)");
01868   _defun(ctx,"UNADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE_SERVICE, "Unadvertise service");
01869 
01870   _defun(ctx,"SET-PARAM",argv[0],(pointer (*)())ROSEUS_SET_PARAM, "key value\n\n""Set parameter");
01871   _defun(ctx,"GET-PARAM",argv[0],(pointer (*)())ROSEUS_GET_PARAM, "key\n\n""Get parameter");
01872   _defun(ctx,"GET-PARAM-CACHED",argv[0],(pointer (*)())ROSEUS_GET_PARAM_CACHED, "Get chached parameter");
01873   _defun(ctx,"HAS-PARAM",argv[0],(pointer (*)())ROSEUS_HAS_PARAM, "Check whether a parameter exists on the parameter server.");
01874   _defun(ctx,"DELETE-PARAM",argv[0],(pointer (*)())ROSEUS_DELETE_PARAM, "key\n\n""Delete parameter from server");
01875 
01876   _defun(ctx,"ROSPACK-FIND",argv[0],(pointer (*)())ROSEUS_ROSPACK_FIND, "Returns ros package path");
01877   _defun(ctx,"ROSPACK-PLUGINS",argv[0],(pointer (*)())ROSEUS_ROSPACK_PLUGINS, "Returns plugins of ros packages");
01878   _defun(ctx,"RESOLVE-NAME",argv[0],(pointer (*)())ROSEUS_RESOLVE_NAME, "Returns ros resolved name");
01879   _defun(ctx,"GET-NAME",argv[0],(pointer (*)())ROSEUS_GETNAME, "Returns current node name");
01880   _defun(ctx,"GET-NAMESPACE",argv[0],(pointer (*)())ROSEUS_GETNAMESPACE, "Returns current node name space");
01881 
01882   _defun(ctx,"ROSEUS-RAW",argv[0],(pointer (*)())ROSEUS, "");
01883   _defun(ctx,"CREATE-NODEHANDLE", argv[0], (pointer (*)())ROSEUS_CREATE_NODEHANDLE, "groupname &optional namespace  ;;\n\n"
01884          "Create ros NodeHandle with given group name. \n"
01885          "\n"
01886          "      (ros::roseus \"test\")\n"
01887          "      (ros::create-node-handle \"mygroup\")\n"
01888          "      (ros::subscribe \"/test\" std_msgs::String #'(lambda (m) (print m)) :groupname \"mygroup\")\n"
01889          "      (while (ros::ok)  (ros::spin-once \"mygroup\"))\n");
01890   _defun(ctx,"SET-LOGGER-LEVEL",argv[0],(pointer (*)())ROSEUS_SET_LOGGER_LEVEL, "");
01891 
01892   _defun(ctx,"GET-HOST",argv[0],(pointer (*)())ROSEUS_GET_HOST, "Get the hostname where the master runs.");
01893   _defun(ctx,"GET-NODES",argv[0],(pointer (*)())ROSEUS_GET_NODES, "Retreives the currently-known list of nodes from the master.");
01894   _defun(ctx,"GET-PORT",argv[0],(pointer (*)())ROSEUS_GET_PORT, "Get the port where the master runs.");
01895   _defun(ctx,"GET-URI",argv[0],(pointer (*)())ROSEUS_GET_URI, "Get the full URI to the master ");
01896   _defun(ctx,"GET-TOPICS",argv[0],(pointer (*)())ROSEUS_GET_TOPICS, "Get the list of topics that are being published by all nodes.");
01897 
01898   defun(ctx,"CREATE-TIMER",argv[0],(pointer (*)())ROSEUS_CREATE_TIMER);
01899 
01900   pointer_update(Spevalof(PACKAGE),p);
01901 
01902   pointer l;
01903   l=makestring(REPOVERSION,strlen(REPOVERSION));
01904   vpush(l);
01905   l=stacknlist(ctx,1);
01906   QREPOVERSION=defvar(ctx, "ROSEUS-REPO-VERSION", l, rospkg);
01907 
01908   M_string remappings;
01909   pointer argp = speval(intern(ctx,"*EUSTOP-ARGUMENT*", strlen("*EUSTOP-ARGUMENT*"),lisppkg));
01910   while(argp!=NIL) {
01911     std::string arg = string((char *)(ccar(argp)->c.str.chars));
01912     // copy from roscpp/src/init.cpp : 432
01913     size_t pos = arg.find(":=");
01914     if (pos != std::string::npos) {
01915       std::string local_name = arg.substr(0, pos);
01916       std::string external_name = arg.substr(pos + 2);
01917       remappings[local_name] = external_name;
01918     }
01919     argp=ccdr(argp);
01920   }
01921   ros::master::init(remappings);
01922   //ros::param::init(remappings);
01923 
01924   return 0;
01925 }
01926 


roseus
Author(s): Kei Okada
autogenerated on Fri Sep 8 2017 03:48:23