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 
00061 #include <ros/init.h>
00062 #include <ros/time.h>
00063 #include <ros/rate.h>
00064 #include <ros/master.h>
00065 #include <ros/this_node.h>
00066 #include <ros/node_handle.h>
00067 #include <ros/service.h>
00068 #include <rospack/rospack.h>
00069 #include <ros/param.h>
00070 #include <ros/callback_queue.h>
00071 
00072 // for eus.h
00073 #define class   eus_class
00074 #define throw   eus_throw
00075 #define export  eus_export
00076 #define vector  eus_vector
00077 #define string  eus_string
00078 
00079 #include "eus.h"
00080 extern "C" {
00081   pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env);
00082   void register_roseus(){
00083     char modname[] = "___roseus";
00084     return add_module_initializer(modname, (pointer (*)())___roseus);}
00085 }
00086 
00087 #undef class
00088 #undef throw
00089 #undef export
00090 #undef vector
00091 #undef string
00092 
00093 namespace ros {
00094   namespace master {
00095     std::string g_uri;
00096     void init(const M_string& remappings);
00097   }
00098   namespace param {
00099     void init(const M_string& remappings);
00100   }
00101 }
00102 
00103 using namespace ros;
00104 using namespace std;
00105 
00106 #define isInstalledCheck \
00107   if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
00108 
00109 class RoseusStaticData
00110 {
00111 public:
00112   RoseusStaticData() {}
00113   ~RoseusStaticData() {
00114   }
00115   boost::shared_ptr<ros::NodeHandle> node;
00116   ros::Rate *rate;
00117   map<string, boost::shared_ptr<Publisher> > mapAdvertised; 
00118   map<string, boost::shared_ptr<Subscriber> > mapSubscribed; 
00119   map<string, boost::shared_ptr<ServiceServer> > mapServiced; 
00120 
00121   map<string, boost::shared_ptr<NodeHandle> > mapHandle; 
00122 };
00123 
00124 static RoseusStaticData s_staticdata;
00125 static bool s_bInstalled = false;
00126 #define s_node s_staticdata.node
00127 #define s_rate s_staticdata.rate
00128 #define s_mapAdvertised s_staticdata.mapAdvertised
00129 #define s_mapSubscribed s_staticdata.mapSubscribed
00130 #define s_mapServiced s_staticdata.mapServiced
00131 #define s_mapHandle s_staticdata.mapHandle
00132 
00133 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,QANON,QNOOUT,QSVNVERSION;
00134 extern pointer LAMCLOSURE;
00135 
00136 /***********************************************************
00137  *   Message wrapper
00138  ************************************************************/
00139 
00140 string getString(pointer message, pointer method) {
00141   context *ctx = current_ctx;
00142   pointer r, curclass;
00143   if ((pointer)findmethod(ctx,method,classof(message),&curclass)!=NIL) {
00144     r = csend(ctx,message,method,0);
00145   } else if ((pointer)findmethod(ctx,K_ROSEUS_GET,classof(message),&curclass) != NIL ) {
00146     r = csend(ctx,message,K_ROSEUS_GET,1,method);
00147   } else {
00148     r = NULL;
00149 #ifdef x86_64
00150     ROS_ERROR("could not find method %s for pointer %lx",
00151               get_string(method), (long unsigned int)message);
00152 #else
00153     ROS_ERROR("could not find method %s for pointer %x",
00154               get_string(method), (unsigned int)message);
00155 #endif
00156   }
00157   if ( !isstring(r) ) {
00158     pointer dest=(pointer)mkstream(ctx,K_OUT,makebuffer(64));
00159     prinx(ctx,message,dest);
00160     pointer str = makestring((char *)dest->c.stream.buffer->c.str.chars,
00161                              intval(dest->c.stream.count));
00162     ROS_ERROR("send %s to %s returns nil", get_string(method), get_string(str));
00163   }
00164   ROS_ASSERT(isstring(r));
00165   string ret = (char *)get_string(r);
00166   return ret;
00167 }
00168 
00169 int getInteger(pointer message, pointer method) {
00170   context *ctx = current_ctx;
00171   pointer a,curclass;
00172   vpush(message);
00173   a = (pointer)findmethod(ctx,method,classof(message),&curclass);
00174   if (a!=NIL) {
00175     pointer r = csend(ctx,message,method,0);
00176     vpop();                     // message
00177     return (ckintval(r));
00178   } else {
00179 #ifdef x86_64
00180     ROS_ERROR("could not find method %s for pointer %lx",
00181               get_string(method), (long unsigned int)message);
00182 #else
00183     ROS_ERROR("could not find method %s for pointer %x",
00184               get_string(method), (unsigned int)message);
00185 #endif
00186     vpop();                     // message
00187   }
00188   return 0;
00189 }
00190 
00191 class EuslispMessage
00192 {
00193 public:
00194   pointer _message;
00195 
00196   EuslispMessage(pointer message) : _message(message) {
00197   }
00198   EuslispMessage(const EuslispMessage &r) {
00199     context *ctx = current_ctx;
00200     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00201     if ( isclass(r._message) ) {
00202       //ROS_ASSERT(isclass(r._message));
00203       vpush(r._message);
00204       _message = makeobject(r._message);
00205       vpush(_message);
00206       csend(ctx,_message,K_ROSEUS_INIT,0);
00207       vpop();                   // _message
00208       vpop();                   // r._message
00209     } else {
00210       ROS_WARN("r._message must be class");prinx(ctx,r._message,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00211       _message = r._message;
00212     }
00213   }
00214   virtual ~EuslispMessage() { }
00215 
00216   virtual void replaceContents (pointer newMessage) {
00217     _message = newMessage;
00218   }
00219 
00220   virtual const string __getDataType() const {
00221     return getString(_message, K_ROSEUS_DATATYPE);
00222   }
00223   virtual const string __getMD5Sum()   const {
00224     return getString(_message, K_ROSEUS_MD5SUM);
00225   }
00226   virtual const string __getMessageDefinition() const {
00227     return getString(_message, K_ROSEUS_DEFINITION);
00228   }
00229   virtual const string __getServiceDataType() const {
00230     return getString(_message, K_ROSEUS_DATATYPE);
00231   }
00232   virtual const string __getServerMD5Sum()    const {
00233     return getString(_message, K_ROSEUS_MD5SUM);
00234   }
00235 
00236   uint32_t serializationLength() const {
00237     context *ctx = current_ctx;
00238     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00239     pointer a,curclass;
00240     a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(_message),&curclass);
00241     ROS_ASSERT(a!=NIL);
00242     return getInteger(_message, K_ROSEUS_SERIALIZATION_LENGTH);
00243   }
00244 
00245   virtual uint8_t *serialize(uint8_t *writePtr, uint32_t seqid) const
00246   {
00247     context *ctx = current_ctx;
00248     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00249     pointer a,curclass;
00250     vpush(_message);            // to avoid GC
00251     uint32_t len = serializationLength();
00252     vpop();                     // pop _message
00253     a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZE,classof(_message),&curclass);
00254     ROS_ASSERT(a!=NIL);
00255     pointer r = csend(ctx,_message,K_ROSEUS_SERIALIZE,0);
00256     ROS_ASSERT(isstring(r));
00257     memcpy(writePtr, get_string(r), len);
00258     //ROS_INFO("serialize");
00259 
00260     return writePtr + len;
00261   }
00262 
00263   virtual uint8_t *deserialize(uint8_t *readPtr, uint32_t sz)
00264   {
00265     context *ctx = current_ctx;
00266     if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
00267     pointer a,curclass;
00268 
00269     if ( sz == 0 ) {
00270       ROS_DEBUG("empty message!");
00271       return readPtr;
00272     }
00273     vpush(_message);
00274     a = (pointer)findmethod(ctx,K_ROSEUS_DESERIALIZE,classof(_message),&curclass);
00275     ROS_ASSERT(a!=NIL);
00276     pointer p = makestring((char *)readPtr, sz);
00277     pointer r = csend(ctx,_message,K_ROSEUS_DESERIALIZE,1,p);
00278     ROS_ASSERT(r!=NIL);
00279     //ROS_INFO("deserialize %d", __serialized_length);
00280     vpop(); // pop _message
00281 
00282     return readPtr + sz;
00283   }
00284 };
00285 
00286 namespace ros{
00287   namespace serialization{
00288 template<> struct Serializer<EuslispMessage> {
00289   template<typename Stream>
00290   inline static void write(Stream& stream, boost::call_traits<EuslispMessage>::param_type t) {
00291     t.serialize(stream.getData(), 0);
00292   }
00293 
00294   template<typename Stream>
00295   inline static void read(Stream& stream, boost::call_traits<EuslispMessage>::reference t) {
00296     t.deserialize(stream.getData(), stream.getLength());
00297   }
00298   inline static uint32_t serializedLength(boost::call_traits<EuslispMessage>::param_type t) {
00299     return t.serializationLength();
00300   }
00301 };
00302   }
00303 }
00304 
00305 /************************************************************
00306  *   Subscriptions
00307  ************************************************************/
00308 class EuslispSubscriptionCallbackHelper : public ros::SubscriptionCallbackHelper {
00309 public:
00310   pointer _scb,_args;
00311   EuslispMessage _msg;
00312 
00313   EuslispSubscriptionCallbackHelper(pointer scb, pointer args,pointer tmpl) :  _args(args), _msg(tmpl) {
00314     context *ctx = current_ctx;
00315     mutex_trylock(&mark_lock);
00316     //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00317     //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00318     if (piscode(scb)) { // compiled code
00319       _scb=scb;
00320     } else if ((ccar(scb))==LAMCLOSURE) { // uncompiled code
00321       if ( ccar(ccdr(scb)) != NIL ) { // function
00322         _scb=ccar(ccdr(scb));
00323       } else { // lambda function
00324         _scb=scb;
00325       }
00326     } else {
00327       ROS_ERROR("subcriptoin callback function install error");
00328     }
00329     // avoid gc
00330     pointer p=gensym(ctx);
00331     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));
00332     mutex_unlock(&mark_lock);
00333   }
00334   ~EuslispSubscriptionCallbackHelper() {
00335       ROS_ERROR("subcriptoin gc");
00336   }
00337   virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams& param) {
00338 #if DEBUG
00339     cerr << __PRETTY_FUNCTION__ << endl;
00340     cerr << "param.length = " << param.length << endl;
00341     cerr << "param.buffer = " << (param.buffer + 4) << endl;
00342     cerr << "c_header == " << param.connection_header << endl;
00343 #endif
00344     ros::VoidConstPtr ptr(new EuslispMessage(_msg));
00345     EuslispMessage *eus_msg = (EuslispMessage *)(ptr.get());
00346     eus_msg->deserialize(param.buffer, param.length);
00347 
00348     return ptr;
00349   }
00350   virtual void call(ros::SubscriptionCallbackHelperCallParams& param) {
00351     EuslispMessage* eus_msg = (EuslispMessage *)((void *)param.event.getConstMessage().get());
00352     context *ctx = current_ctx;
00353     pointer argp=_args;
00354     int argc=0;
00355     //ROS_WARN("func");prinx(ctx,_scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00356     //ROS_WARN("argc");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00357     vpush(eus_msg->_message);    // to avoid GC
00358     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
00359       ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
00360     }
00361     
00362     while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
00363     vpush((pointer)(eus_msg->_message));argc++;
00364     
00365     ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
00366     while(argc-->0)vpop();
00367     vpop();    // remove eus_msg._message
00368   }
00369   virtual const std::type_info& getTypeInfo() {
00370     return typeid(EuslispMessage);
00371   }
00372   virtual bool isConst(){
00373     return true;
00374   }
00375 };
00376 
00377 /************************************************************
00378  *   ServiceCall
00379  ************************************************************/
00380 class EuslispServiceCallbackHelper : public ros::ServiceCallbackHelper {
00381 public:
00382   pointer _scb, _args;
00383   EuslispMessage _req, _res;
00384   string md5, datatype, requestDataType, responseDataType,
00385     requestMessageDefinition, responseMessageDefinition;
00386 
00387   EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass) : _args(args), _req(reqclass), _res(resclass), md5(smd5), datatype(sdatatype) {
00388     context *ctx = current_ctx;
00389     mutex_trylock(&mark_lock);
00390     //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00391     //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
00392 
00393     if (piscode(scb)) { // compiled code
00394       _scb=scb;
00395     } else if ((ccar(scb))==LAMCLOSURE) {
00396       if ( ccar(ccdr(scb)) != NIL ) { // function
00397         _scb=ccar(ccdr(scb));
00398       } else { // lambda function
00399         _scb=scb;
00400       }
00401     } else  {
00402       ROS_ERROR("service callback function install error");
00403     }
00404     // avoid gc
00405     pointer p=gensym(ctx);
00406     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));
00407 
00408     requestDataType = _req.__getDataType();
00409     responseDataType = _res.__getDataType();
00410     requestMessageDefinition = _req.__getMessageDefinition();
00411     responseMessageDefinition = _res.__getMessageDefinition();
00412     mutex_unlock(&mark_lock);
00413   }
00414   ~EuslispServiceCallbackHelper() { }
00415 
00416   virtual boost::shared_ptr<EuslispMessage> createRequest() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_req)); }
00417   virtual boost::shared_ptr<EuslispMessage> createResponse() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_res)); }
00418 
00419   virtual std::string getMD5Sum() { return md5; }
00420   virtual std::string getDataType() { return datatype; }
00421   virtual std::string getRequestDataType() { return requestDataType; }
00422   virtual std::string getResponseDataType() { return responseDataType; }
00423   virtual std::string getRequestMessageDefinition() { return requestMessageDefinition; }
00424   virtual std::string getResponseMessageDefinition() { return responseMessageDefinition; }
00425 
00426   virtual bool call(ros::ServiceCallbackHelperCallParams& params) {
00427     context *ctx = current_ctx;
00428     pointer r, argp=_args;
00429     int argc=0;
00430 
00431     vpush(_res._message);       // _res._message
00432     vpush(_req._message);       // _res._message, _req._message
00433 
00434     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
00435       ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
00436     }
00437     // Deserialization
00438     EuslispMessage eus_msg(_req);
00439     vpush(eus_msg._message);    // _res._message, _req._message, eus_msg._message
00440     eus_msg.deserialize(params.request.message_start, params.request.num_bytes);
00441 
00442     while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
00443     vpush((pointer) eus_msg._message);argc++;
00444 
00445     r = ufuncall(ctx, (ctx->callfp?ctx->callfp->form:NIL),
00446                  _scb, (pointer)(ctx->vsp-argc),
00447                  NULL, argc);
00448     while(argc-->0)vpop();// _res._message, _req._message, eus_msg._message
00449     vpush(r); // _res._message, _req._message, eus_msg._message, r, 
00450     
00451     // Serializaion
00452     EuslispMessage eus_res(_res);
00453     eus_res.replaceContents(r);
00454     vpush(eus_res._message);    // _res._message, _req._message, eus_msg._message, r, eus_res._message
00455     
00456     uint32_t serialized_length = eus_res.serializationLength();
00457     params.response.num_bytes = serialized_length + 5; // add 5 bytes of message header
00458     params.response.buf.reset (new uint8_t[params.response.num_bytes]);
00459     params.response.message_start = 0;
00460 
00461     // SerializedResponseMessage
00462     uint8_t *tmp = params.response.buf.get();
00463     *tmp++ = 1; // 1 byte of success services flag, now always set true
00464     *tmp++ = (uint8_t)((serialized_length >> 0) & 0xFF); // 4bytes of message length
00465     *tmp++ = (uint8_t)((serialized_length >> 8) & 0xFF);
00466     *tmp++ = (uint8_t)((serialized_length >> 16) & 0xFF);
00467     *tmp++ = (uint8_t)((serialized_length >> 24) & 0xFF);
00468     eus_res.serialize(tmp, 0);
00469 #if DEBUG
00470     cerr << "num bytes = " << params.response.num_bytes << endl;
00471     ROS_INFO("message_start =  %X",params.response.message_start);
00472     ROS_INFO("message_ptr =  %X",params.response.buf.get());
00473     tmp = params.response.buf.get();
00474     for(int i=0;i<params.response.num_bytes;i++){
00475       ROS_INFO("%X", tmp[i]);
00476     }
00477 #endif
00478     vpop(); // _res._message, _req._message, eus_msg._message, r, eus_res._message
00479     vpop(); // _res._message, _req._message, eus_msg._message, r
00480     vpop(); // _res._message, _req._message, eus_msg._message
00481     vpop(); // _res._message, _req._message,
00482     vpop(); // _res._message
00483     return(T);
00484   }
00485 };
00486 
00487 void roseusSignalHandler(int sig)
00488 {
00489     // memoize for euslisp handler...
00490     context *ctx=euscontexts[thr_self()];
00491     ctx->intsig = sig;
00492 }
00493 
00494 /************************************************************
00495  *   EUSLISP functions
00496  ************************************************************/
00497 pointer ROSEUS(register context *ctx,int n,pointer *argv)
00498 {
00499   char name[256] = "";
00500   uint32_t options = 0;
00501   int cargc = 0;
00502   char *cargv[32];
00503 
00504   if( s_bInstalled ) {
00505     ROS_WARN("ROSEUS is already installed as %s", ros::this_node::getName().c_str());
00506     return (T);
00507   }
00508 
00509   ckarg(3);
00510   if (isstring(argv[0]))
00511     strncpy(name,(char *)(argv[0]->c.str.chars),255);
00512   else error(E_NOSTRING);
00513   options = ckintval(argv[1]);
00514   pointer p = argv[2];
00515   if (islist(p)) {
00516     while (1) {
00517       if (!iscons(p)) break;
00518       cargv[cargc]=(char *)((ccar(p))->c.str.chars);
00519       cargc++;
00520       p=ccdr(p);
00521     }
00522   } else error(E_NOSEQ);
00523 
00524   for (unsigned int i=0; i < strlen(name); i++)
00525     if ( ! isalpha(name[i]) ) name[i] = '_';
00526 
00527   K_ROSEUS_MD5SUM   = defkeyword(ctx,"MD5SUM-");
00528   K_ROSEUS_DATATYPE = defkeyword(ctx,"DATATYPE-");
00529   K_ROSEUS_DEFINITION = defkeyword(ctx,"DEFINITION-");
00530   K_ROSEUS_SERIALIZATION_LENGTH = defkeyword(ctx,"SERIALIZATION-LENGTH");
00531   K_ROSEUS_SERIALIZE   = defkeyword(ctx,"SERIALIZE");
00532   K_ROSEUS_DESERIALIZE = defkeyword(ctx,"DESERIALIZE");
00533   K_ROSEUS_GET  = defkeyword(ctx,"GET");
00534   K_ROSEUS_INIT = defkeyword(ctx,"INIT");
00535   K_ROSEUS_REQUEST  = defkeyword(ctx,"REQUEST");
00536   K_ROSEUS_RESPONSE = defkeyword(ctx,"RESPONSE");
00537   K_ROSEUS_GROUPNAME = defkeyword(ctx,"GROUPNAME");
00538 
00539   s_mapAdvertised.clear();
00540   s_mapSubscribed.clear();
00541   s_mapServiced.clear();
00542   s_mapHandle.clear();
00543   
00544   /*
00545     force to flag ros::init_options::NoSigintHandler.
00546     In fact, this code make no sence, because we steals
00547     SIGINT handler by the following `signal'.
00548    */
00549   options |= ros::init_options::NoSigintHandler;
00550 
00551   /*
00552     clear ros::master::g_uri which is defined in ros::master::init in __roseus.
00553     this occurs if user set unix::setenv("ROS_MASTER_URI") between __roseus and
00554     ROSEUS.
00555    */
00556   if (!ros::master::g_uri.empty()) {
00557     if ( ros::master::g_uri != getenv("ROS_MASTER_URI") ) {
00558       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"));
00559       ros::master::g_uri.clear();
00560     }
00561   }
00562   try {
00563     ros::init(cargc, cargv, name, options);
00564   } catch (const ros::InvalidNameException &e) {
00565     ROS_ERROR("%s",e.what());
00566     error(E_MISMATCHARG);
00567     return(NIL);
00568   }
00569 
00570   s_node.reset(new ros::NodeHandle());
00571   s_rate = new ros::Rate(50);
00572 
00573   s_bInstalled = true;
00574 
00575   // install signal handler for sigint. DO NOT call unix:signal after
00576   // ros::roseus
00577   signal(SIGINT, roseusSignalHandler);
00578   return (T);
00579 }
00580 
00581 pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx,int n,pointer *argv)
00582 {
00583   isInstalledCheck;
00584   string groupname;
00585   string ns;
00586 
00587   ckarg2(1, 2);
00588   // ;; arguments ;;
00589   // groupname [ namespace ]
00590 
00591   if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
00592   else error(E_NOSTRING);
00593   if ( n > 1 ) {
00594     if(isstring(argv[1])) ns.assign((char *)get_string(argv[1]));
00595     else error(E_NOSTRING);
00596   }
00597 
00598   if( s_mapHandle.find(groupname) != s_mapHandle.end() ) {
00599     ROS_WARN("groupname %s is already used", groupname.c_str());
00600     return (NIL);
00601   }
00602 
00603   boost::shared_ptr<NodeHandle> hd;
00604   if ( n > 1 ) {
00605     hd = boost::shared_ptr<NodeHandle> (new NodeHandle(ns));
00606     s_mapHandle[groupname] = hd;
00607   } else {
00608     hd = boost::shared_ptr<NodeHandle>(new NodeHandle());
00609     s_mapHandle[groupname] = hd;
00610   }
00611   //add callbackqueue to hd
00612   hd->setCallbackQueue( new CallbackQueue() );
00613 
00614   return (T);
00615 }
00616 
00617 pointer ROSEUS_SPIN(register context *ctx,int n,pointer *argv)
00618 {
00619   isInstalledCheck;
00620   while (ctx->intsig==0) {
00621     ros::spinOnce();
00622     s_rate->sleep();
00623   }
00624   return (NIL);
00625 }
00626 
00627 pointer ROSEUS_SPINONCE(register context *ctx,int n,pointer *argv)
00628 {
00629   isInstalledCheck;
00630   ckarg2(0, 1);
00631   // ;; arguments ;;
00632   // [ groupname ]
00633 
00634   if ( n > 0 ) {
00635     string groupname;
00636     if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
00637     else error(E_NOSTRING);
00638 
00639     map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
00640     if( it == s_mapHandle.end() ) {
00641       ROS_WARN("groupname %s is missing", groupname.c_str());
00642       return (T);
00643     }
00644     boost::shared_ptr<NodeHandle > hdl = (it->second);
00645     // spin this nodehandle
00646     ((CallbackQueue *)hdl->getCallbackQueue())->callAvailable();
00647 
00648     return (NIL);
00649   } else {
00650     ros::spinOnce();
00651     return (NIL);
00652   }
00653 }
00654 
00655 pointer ROSEUS_TIME_NOW(register context *ctx,int n,pointer *argv)
00656 {
00657   isInstalledCheck;
00658   pointer timevec;
00659   ros::Time t = ros::Time::now();
00660 
00661   timevec=makevector(C_INTVECTOR,2);
00662   vpush(timevec);
00663   timevec->c.ivec.iv[0]=t.sec;
00664   timevec->c.ivec.iv[1]=t.nsec;
00665   vpop();
00666   return (timevec);
00667 }
00668 
00669 pointer ROSEUS_RATE(register context *ctx,int n,pointer *argv)
00670 {
00671   isInstalledCheck;
00672   numunion nu;
00673   ckarg(1);
00674   float timeout=ckfltval(argv[0]);
00675   s_rate = new ros::Rate(timeout);
00676   return(T);
00677 }
00678 
00679 pointer ROSEUS_SLEEP(register context *ctx,int n,pointer *argv)
00680 {
00681   isInstalledCheck;
00682   s_rate->sleep();
00683   return (T);
00684 }
00685 
00686 pointer ROSEUS_OK(register context *ctx,int n,pointer *argv)
00687 {
00688   if (ros::ok()) {
00689     return (T);
00690   } else {
00691     return (NIL);
00692   }
00693 }
00694 
00695 
00696 #define def_rosconsole_formatter(funcname, rosfuncname)         \
00697   pointer funcname(register context *ctx,int n,pointer *argv)   \
00698   { pointer *argv2,msg;                                         \
00699     int argc2;                                                  \
00700     argc2 = n+1;                                                \
00701     argv2 = (pointer *)malloc(sizeof(pointer)*argc2);           \
00702     argv2[0] = NIL;                                             \
00703     for(int i=0;i<n;i++) argv2[i+1]=argv[i] ;                   \
00704     msg = XFORMAT(ctx, argc2, argv2);                           \
00705     rosfuncname("%s", msg->c.str.chars);                        \
00706     free(argv2);                                                \
00707     return (T);                                                 \
00708   }
00709 
00710 def_rosconsole_formatter(ROSEUS_ROSDEBUG, ROS_DEBUG)
00711 def_rosconsole_formatter(ROSEUS_ROSINFO,  ROS_INFO)
00712 def_rosconsole_formatter(ROSEUS_ROSWARN,  ROS_WARN)
00713 def_rosconsole_formatter(ROSEUS_ROSERROR, ROS_ERROR)
00714 def_rosconsole_formatter(ROSEUS_ROSFATAL, ROS_FATAL)
00715 
00716 pointer ROSEUS_EXIT(register context *ctx,int n,pointer *argv)
00717 {
00718   ROS_INFO("%s", __PRETTY_FUNCTION__);
00719   if( s_bInstalled ) {
00720     ROS_INFO("exiting roseus %ld", (n==0)?n:ckintval(argv[0]));
00721     s_mapAdvertised.clear();
00722     s_mapSubscribed.clear();
00723     s_mapServiced.clear();
00724     s_mapHandle.clear();
00725     ros::shutdown();
00726   }
00727   if (n==0) _exit(0);
00728   else _exit(ckintval(argv[0]));
00729 }
00730 
00731 /************************************************************
00732  *   ROSEUS Publisher/Subscriber
00733  ************************************************************/
00734 pointer ROSEUS_SUBSCRIBE(register context *ctx,int n,pointer *argv)
00735 {
00736   isInstalledCheck;
00737   string topicname;
00738   pointer message, fncallback, args;
00739   int queuesize = 1;
00740   NodeHandle *lnode = s_node.get();
00741 
00742   // ;; arguments ;;
00743   // topicname message_type callbackfunc args0 ... argsN [ queuesize ] [ :groupname groupname ]
00744 
00745   if (n > 1 && issymbol(argv[n-2]) && isstring(argv[n-1])) {
00746     if (argv[n-2] == K_ROSEUS_GROUPNAME) {
00747       string groupname;
00748       groupname.assign((char *)get_string(argv[n-1]));
00749       map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
00750       if( it != s_mapHandle.end() ) {
00751         lnode = (it->second).get();
00752       } else {
00753         ROS_WARN("groupname %s is missing", groupname.c_str());
00754         return (NIL);
00755       }
00756       n -= 2;
00757     }
00758   }
00759   if (isint(argv[n-1])) {queuesize = ckintval(argv[n-1]);n--;}
00760   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00761   else error(E_NOSTRING);
00762   // TODO:need error checking
00763   message = argv[1];
00764   fncallback = argv[2];
00765   args=NIL;
00766   for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
00767 
00768   EuslispMessage msg(message);
00769    boost::shared_ptr<SubscriptionCallbackHelper> *callback =
00770      (new boost::shared_ptr<SubscriptionCallbackHelper>
00771       (new EuslispSubscriptionCallbackHelper(fncallback, args, message)));
00772   SubscribeOptions so(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType());
00773   so.helper = *callback;
00774   Subscriber subscriber = lnode->subscribe(so);
00775   boost::shared_ptr<Subscriber> sub = boost::shared_ptr<Subscriber>(new Subscriber(subscriber));
00776   if ( !!sub ) {
00777     s_mapSubscribed[topicname] = sub;
00778   } else {
00779     ROS_ERROR("s_mapSubscribed");
00780   }
00781 
00782   return (T);
00783 }
00784 
00785 pointer ROSEUS_UNSUBSCRIBE(register context *ctx,int n,pointer *argv)
00786 {
00787   string topicname;
00788 
00789   ckarg(1);
00790   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00791   else error(E_NOSTRING);
00792 
00793   bool bSuccess = s_mapSubscribed.erase(topicname)>0;
00794 
00795   return (bSuccess?T:NIL);
00796 }
00797 
00798 pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx,int n,pointer *argv)
00799 {
00800   string topicname;
00801   int ret;
00802 
00803   ckarg(1);
00804   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00805   else error(E_NOSTRING);
00806 
00807   bool bSuccess = false;
00808   map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
00809   if( it != s_mapSubscribed.end() ) {
00810     boost::shared_ptr<Subscriber> subscriber = (it->second);
00811     ret = subscriber->getNumPublishers();
00812     bSuccess = true;
00813   }
00814 
00815   if ( ! bSuccess ) {
00816     ROS_ERROR("attempted to getNumPublishers to topic %s, which was not " \
00817               "previously subscribed. call (ros::subscribe \"%s\") first.",
00818               topicname.c_str(), topicname.c_str());
00819   }
00820 
00821   return (bSuccess?(makeint(ret)):NIL);
00822 }
00823 
00824 pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx,int n,pointer *argv)
00825 {
00826   string topicname;
00827   string ret;
00828 
00829   ckarg(1);
00830   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00831   else error(E_NOSTRING);
00832 
00833   bool bSuccess = false;
00834   map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
00835   if( it != s_mapSubscribed.end() ) {
00836     boost::shared_ptr<Subscriber> subscriber = (it->second);
00837     ret = subscriber->getTopic();
00838     bSuccess = true;
00839   }
00840 
00841   if ( ! bSuccess ) {
00842     ROS_ERROR("attempted to getTopic to topic %s, which was not " \
00843               "previously advertised. call (ros::advertise \"%s\") first.",
00844               topicname.c_str(), topicname.c_str());
00845   }
00846 
00847   return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
00848 }
00849 
00850 pointer ROSEUS_ADVERTISE(register context *ctx,int n,pointer *argv)
00851 {
00852   isInstalledCheck;
00853   string topicname;
00854   pointer message;
00855   int queuesize = 1;
00856   bool latch = false;
00857 
00858   ckarg2(2,4);
00859   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00860   else error(E_NOSTRING);
00861   message = argv[1];
00862   if ( n > 2 ) {
00863     queuesize = ckintval(argv[2]);
00864   }
00865   if ( n > 3 ) {
00866     latch = (argv[3]!=NIL ? true : false);
00867   }
00868 
00869   if( s_mapAdvertised.find(topicname) != s_mapAdvertised.end() ) {
00870     ROS_INFO("topic %s already advertised", topicname.c_str());
00871     return (NIL);
00872   }
00873 
00874   EuslispMessage msg(message);
00875   AdvertiseOptions ao(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType(), msg.__getMessageDefinition());
00876   ao.latch = latch;
00877   Publisher publisher = s_node->advertise(ao);
00878   boost::shared_ptr<Publisher> pub = boost::shared_ptr<Publisher>(new Publisher(publisher));
00879   if ( !!pub ) {
00880     s_mapAdvertised[topicname] = pub;
00881   } else {
00882     ROS_ERROR("s_mapAdvertised");
00883   }
00884 
00885   return (T);
00886 }
00887 
00888 pointer ROSEUS_UNADVERTISE(register context *ctx,int n,pointer *argv)
00889 {
00890   string topicname;
00891 
00892   ckarg(1);
00893   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00894   else error(E_NOSTRING);
00895 
00896   bool bSuccess = s_mapAdvertised.erase(topicname)>0;
00897 
00898   return (bSuccess?T:NIL);
00899 }
00900 
00901 pointer ROSEUS_PUBLISH(register context *ctx,int n,pointer *argv)
00902 {
00903   isInstalledCheck;
00904   string topicname;
00905   pointer emessage;
00906 
00907   ckarg(2);
00908   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00909   else error(E_NOSTRING);
00910   emessage = argv[1];
00911 
00912   bool bSuccess = false;
00913   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00914   if( it != s_mapAdvertised.end() ) {
00915     boost::shared_ptr<Publisher> publisher = (it->second);
00916     EuslispMessage message(emessage);
00917     publisher->publish(message);
00918     bSuccess = true;
00919   }
00920 
00921   if ( ! bSuccess ) {
00922     ROS_ERROR("attempted to publish to topic %s, which was not " \
00923               "previously advertised. call (ros::advertise \"%s\") first.",
00924               topicname.c_str(), topicname.c_str());
00925   }
00926 
00927   return (T);
00928 }
00929 
00930 pointer ROSEUS_GETNUMSUBSCRIBERS(register context *ctx,int n,pointer *argv)
00931 {
00932   string topicname;
00933   int ret;
00934 
00935   ckarg(1);
00936   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00937   else error(E_NOSTRING);
00938 
00939   bool bSuccess = false;
00940   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00941   if( it != s_mapAdvertised.end() ) {
00942     boost::shared_ptr<Publisher> publisher = (it->second);
00943     ret = publisher->getNumSubscribers();
00944     bSuccess = true;
00945   }
00946 
00947   if ( ! bSuccess ) {
00948     ROS_ERROR("attempted to getNumSubscribers to topic %s, which was not " \
00949               "previously advertised. call (ros::advertise \"%s\") first.",
00950               topicname.c_str(), topicname.c_str());
00951   }
00952 
00953   return (bSuccess?(makeint(ret)):NIL);
00954 }
00955 
00956 pointer ROSEUS_GETTOPICPUBLISHER(register context *ctx,int n,pointer *argv)
00957 {
00958   string topicname;
00959   string ret;
00960 
00961   ckarg(1);
00962   if (isstring(argv[0])) topicname.assign((char *)get_string(argv[0]));
00963   else error(E_NOSTRING);
00964 
00965   bool bSuccess = false;
00966   map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
00967   if( it != s_mapAdvertised.end() ) {
00968     boost::shared_ptr<Publisher> publisher = (it->second);
00969     ret = publisher->getTopic();
00970     bSuccess = true;
00971   }
00972 
00973   if ( ! bSuccess ) {
00974     ROS_ERROR("attempted to getTopic to topic %s, which was not " \
00975               "previously advertised. call (ros::advertise \"%s\") first.",
00976               topicname.c_str(), topicname.c_str());
00977   }
00978 
00979   return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
00980 }
00981 
00982 /************************************************************
00983  *   ROSEUS ServiceCall
00984  ************************************************************/
00985 pointer ROSEUS_WAIT_FOR_SERVICE(register context *ctx,int n,pointer *argv)
00986 {
00987   isInstalledCheck;
00988   string service;
00989 
00990   ckarg2(1,2);
00991   if (isstring(argv[0])) service.assign((char *)(argv[0]->c.str.chars));
00992   else error(E_NOSTRING);
00993 
00994   int32_t timeout = -1;
00995 
00996   if( n > 1 )
00997     timeout = (int32_t)ckintval(argv[1]);
00998 
00999   bool bSuccess = service::waitForService(ros::names::resolve(service), ros::Duration(timeout));
01000 
01001   return (bSuccess?T:NIL);
01002 }
01003 
01004 pointer ROSEUS_SERVICE_EXISTS(register context *ctx,int n,pointer *argv)
01005 {
01006   isInstalledCheck;
01007   string service;
01008 
01009   ckarg(1);
01010   if (isstring(argv[0])) service.assign((char *)(argv[0]->c.str.chars));
01011   else error(E_NOSTRING);
01012 
01013   bool bSuccess = service::exists(ros::names::resolve(service), true);
01014 
01015   return (bSuccess?T:NIL);
01016 }
01017 
01018 pointer ROSEUS_SERVICE_CALL(register context *ctx,int n,pointer *argv)
01019 {
01020   isInstalledCheck;
01021   string service;
01022   pointer emessage;
01023   bool persist = false;
01024 
01025   ckarg(2);
01026   if (isstring(argv[0])) service.assign((char *)(argv[0]->c.str.chars));
01027   else error(E_NOSTRING);
01028   emessage = argv[1];
01029 
01030   EuslispMessage request(emessage);
01031   vpush(request._message);      // to avoid GC, it may not be required...
01032   EuslispMessage response(csend(ctx,emessage,K_ROSEUS_RESPONSE,0));
01033   vpush(response._message);     // to avoid GC, its important
01034   ServiceClientOptions sco(ros::names::resolve(service), request.__getMD5Sum(), persist, M_string());
01035   ServiceClient client = s_node->serviceClient(sco);
01036   ServiceClient* srv = new ServiceClient(client);
01037   // NEED FIX
01038   bool bSuccess =  srv->call(request, response, request.__getMD5Sum());
01039   vpop();                       // pop response._message
01040   vpop();                       // pop request._message
01041   if ( ! bSuccess ) {
01042     ROS_ERROR("attempted to call service  %s, but failed ",
01043               ros::names::resolve(service).c_str());
01044   }
01045 
01046   return (response._message);
01047 }
01048 
01049 pointer ROSEUS_ADVERTISE_SERVICE(register context *ctx,int n,pointer *argv)
01050 {
01051   isInstalledCheck;
01052   string service;
01053   pointer emessage;
01054   pointer fncallback, args;
01055 
01056   if (isstring(argv[0])) service.assign((char *)get_string(argv[0]));
01057   else error(E_NOSTRING);
01058   emessage = argv[1];
01059   fncallback = argv[2];
01060   args=NIL;
01061   for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
01062   if( s_mapServiced.find(service) != s_mapServiced.end() ) {
01063     ROS_INFO("service %s already advertised", service.c_str());
01064     return (NIL);
01065   }
01066 
01067   EuslispMessage message(emessage);
01068   vpush(message._message);      // to avoid GC in csend
01069   pointer request(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_REQUEST));
01070   pointer response(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_RESPONSE));
01071   vpop();                       // pop message._message
01072   boost::shared_ptr<EuslispServiceCallbackHelper> *callback =
01073     (new boost::shared_ptr<EuslispServiceCallbackHelper>
01074      (new EuslispServiceCallbackHelper(fncallback, args, message.__getMD5Sum(),
01075                                        message.__getDataType(), request, response)));
01076   AdvertiseServiceOptions aso;
01077   aso.service.assign(service);
01078   aso.datatype = (*callback->get()).getDataType();
01079   aso.md5sum = (*callback->get()).getMD5Sum();
01080   aso.req_datatype = (*callback->get()).getRequestDataType();
01081   aso.res_datatype = (*callback->get()).getResponseDataType();
01082   aso.helper = *callback;
01083   ServiceServer server = s_node->advertiseService(aso);
01084   boost::shared_ptr<ServiceServer> ser = boost::shared_ptr<ServiceServer>(new ServiceServer(server));
01085   if ( !!ser ) {
01086     s_mapServiced[service] = ser;
01087   } else {
01088     ROS_ERROR("s_mapServiced");
01089   }
01090 
01091   return (T);
01092 }
01093 
01094 pointer ROSEUS_UNADVERTISE_SERVICE(register context *ctx,int n,pointer *argv)
01095 {
01096   string service;
01097 
01098   ckarg(1);
01099   if (isstring(argv[0])) service.assign((char *)get_string(argv[0]));
01100   else error(E_NOSTRING);
01101 
01102   ROS_DEBUG("unadvertise %s", service.c_str());
01103   bool bSuccess = s_mapServiced.erase(service)>0;
01104 
01105   return (bSuccess?T:NIL);
01106 }
01107 
01108 pointer ROSEUS_SET_PARAM(register context *ctx,int n,pointer *argv)
01109 {
01110   numunion nu;
01111   string key;
01112   string s;
01113   double d;
01114   int i;
01115 
01116   ckarg(2);
01117   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01118   else error(E_NOSTRING);
01119   if ( isstring(argv[1]) ) {
01120     s.assign((char *)get_string(argv[1]));
01121     ros::param::set(key,s);
01122   } else if (isint(argv[1])) {
01123     i = intval(argv[1]);
01124     ros::param::set(key,i);
01125   } else if (isflt(argv[1])) {
01126     d = fltval(argv[1]);
01127     ros::param::set(key,d);
01128   } else {
01129     error(E_MISMATCHARG);
01130   }
01131   return (T);
01132 }
01133 
01134 pointer XmlRpcToEusList(register context *ctx, XmlRpc::XmlRpcValue param_list)
01135 {
01136     numunion nu;
01137     pointer ret, first;
01138     ret = cons(ctx, NIL, NIL);
01139     first = ret;
01140     vpush(ret);
01141     if ( param_list.getType() == XmlRpc::XmlRpcValue::TypeArray ){
01142         for ( int i = 0; i < param_list.size(); i++){
01143             if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeBoolean ){
01144                 if ( param_list[i] ){
01145                     ccdr(ret) = cons(ctx, T, NIL);
01146                     ret = ccdr(ret);
01147                 } else {
01148                     ccdr(ret) = cons(ctx, NIL, NIL);
01149                     ret = ccdr(ret);
01150                 }
01151             }
01152             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble ){
01153                 ccdr(ret) = cons(ctx, makeflt((double)param_list[i]), NIL);
01154                 ret = ccdr(ret);
01155             }
01156             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeInt ){
01157                 ccdr(ret) = cons(ctx, makeint((int)param_list[i]), NIL);
01158                 ret = ccdr(ret);
01159             }
01160             else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeString ){
01161                 std::string str = param_list[i];
01162                 ccdr(ret) = cons(ctx, makestring((char*)str.c_str(), ((std::string)param_list[i]).length()), NIL);
01163                 ret = ccdr(ret);
01164             }
01165             else {
01166                 ROS_FATAL("unkown rosparam type!");
01167                 vpop();         // remove vpush(ret)
01168                 return NIL;
01169             }
01170         }
01171         vpop();                 // remove vpush(ret)
01172         return ccdr(first);
01173     } else
01174         return (NIL);
01175 }
01176 
01177 pointer ROSEUS_GET_PARAM(register context *ctx,int n,pointer *argv)
01178 {
01179   numunion nu;
01180   string key;
01181 
01182   ckarg2(1,2);
01183   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01184   else error(E_NOSTRING);
01185 
01186   string s;
01187   double d;
01188   bool b;
01189   int i;
01190   pointer ret;
01191   XmlRpc::XmlRpcValue param_list;
01192 
01193   if ( ros::param::get(key, s) ) {
01194     ret = makestring((char *)s.c_str(), s.length());
01195   } else if ( ros::param::get(key, d) ) {
01196     ret = makeflt(d);
01197   } else if ( ros::param::get(key, i) ) {
01198     ret = makeint(i);
01199   } else if ( ros::param::get(key, b) ) {
01200       if ( b == true )
01201           ret = T;
01202       else
01203           ret = NIL;
01204   } else if (ros::param::get(key, param_list)){
01205       ret = XmlRpcToEusList(ctx, param_list);
01206   }else {
01207     if ( n == 2 ) {
01208       ret = copyobj(ctx,argv[1]);
01209     } else {
01210       ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
01211       ret = NIL;
01212     }
01213   }
01214   return (ret);
01215 }
01216 
01217 pointer ROSEUS_GET_PARAM_CASHED(register context *ctx,int n,pointer *argv)
01218 {
01219   numunion nu;
01220   string key;
01221 
01222   ckarg2(1,2);
01223   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01224   else error(E_NOSTRING);
01225 
01226   string s;
01227   double d;
01228   int i;
01229   bool b;
01230   pointer ret;
01231   XmlRpc::XmlRpcValue param_list;
01232   if ( ros::param::getCached(key, s) ) {
01233     ret = makestring((char *)s.c_str(), s.length());
01234   } else if ( ros::param::getCached(key, d) ) {
01235     ret = makeflt(d);
01236   } else if ( ros::param::getCached(key, i) ) {
01237     ret = makeint(i);
01238   } else if ( ros::param::getCached(key, b) ) {
01239       if ( b == true )
01240           ret = T;
01241       else
01242           ret = NIL;
01243   } else if (ros::param::getCached(key, param_list)){
01244       ret = XmlRpcToEusList(ctx, param_list);
01245   } else {
01246     if ( n == 2 ) {
01247       ret = copyobj(ctx,argv[1]);
01248     } else {
01249       ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
01250       ret = NIL;
01251     }
01252   }
01253   return (ret);
01254 }
01255 
01256 pointer ROSEUS_HAS_PARAM(register context *ctx,int n,pointer *argv)
01257 {
01258   string key;
01259 
01260   ckarg(1);
01261   if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
01262   else error(E_NOSTRING);
01263 
01264   return((ros::param::has(key))?(T):(NIL));
01265 }
01266 
01267 pointer ROSEUS_ROSPACK_FIND(register context *ctx,int n,pointer *argv)
01268 {
01269   ckarg(1);
01270 
01271   string pkg;
01272   if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
01273   else error(E_NOSTRING);
01274 
01275   try {
01276 #ifdef ROSPACK_EXPORT
01277       rospack::ROSPack rp;
01278       rospack::Package *p = rp.get_pkg(pkg);
01279       if (p!=NULL) return(makestring((char *)p->path.c_str(),p->path.length()));
01280 #else
01281       rospack::Rospack rp;
01282       std::vector<std::string> search_path;
01283       rp.getSearchPathFromEnv(search_path);
01284       rp.crawl(search_path, 1);
01285       std::string path;
01286       if (rp.find(pkg,path)==true) return(makestring((char *)path.c_str(),path.length()));
01287 #endif
01288   } catch (runtime_error &e) {
01289   }
01290   return(NIL);
01291 }
01292 
01293 pointer ROSEUS_RESOLVE_NAME(register context *ctx,int n,pointer *argv)
01294 {
01295   ckarg(1);
01296   if (!isstring(argv[0])) error(E_NOSTRING);
01297   std::string src;
01298   src.assign((char *)(argv[0]->c.str.chars));
01299   std::string dst = ros::names::resolve(src);
01300   return(makestring((char *)dst.c_str(), dst.length()));
01301 }
01302 
01303 pointer ROSEUS_GETNAME(register context *ctx,int n,pointer *argv)
01304 {
01305   ckarg(0);
01306   return(makestring((char *)ros::this_node::getName().c_str(),
01307                     ros::this_node::getName().length()));
01308 }
01309 
01310 pointer ROSEUS_GETNAMESPACE(register context *ctx,int n,pointer *argv)
01311 {
01312   ckarg(0);
01313   return(makestring((char *)ros::this_node::getNamespace().c_str(),
01314                     ros::this_node::getNamespace().length()));
01315 }
01316 
01317 /************************************************************
01318  *   __roseus
01319  ************************************************************/
01320 
01321 pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
01322 {
01323   pointer rospkg,p=Spevalof(PACKAGE);
01324   rospkg=findpkg(makestring("ROS",3));
01325   if (rospkg == 0) rospkg=makepkg(ctx,makestring("ROS", 3),NIL,NIL);
01326   Spevalof(PACKAGE)=rospkg;
01327 
01328   QANON=defvar(ctx,"*ANONYMOUS-NAME*",makeint(ros::init_options::AnonymousName),rospkg);
01329   QNOOUT=defvar(ctx,"*NO-ROSOUT*",makeint(ros::init_options::NoRosout),rospkg);
01330   defun(ctx,"SPIN",argv[0],(pointer (*)())ROSEUS_SPIN);
01331   defun(ctx,"SPIN-ONCE",argv[0],(pointer (*)())ROSEUS_SPINONCE);
01332   defun(ctx,"TIME-NOW-RAW",argv[0],(pointer (*)())ROSEUS_TIME_NOW);
01333   defun(ctx,"RATE",argv[0],(pointer (*)())ROSEUS_RATE);
01334   defun(ctx,"SLEEP",argv[0],(pointer (*)())ROSEUS_SLEEP);
01335   defun(ctx,"OK",argv[0],(pointer (*)())ROSEUS_OK);
01336 
01337   defun(ctx,"ROS-DEBUG",argv[0],(pointer (*)())ROSEUS_ROSDEBUG);
01338   defun(ctx,"ROS-INFO",argv[0],(pointer (*)())ROSEUS_ROSINFO);
01339   defun(ctx,"ROS-WARN",argv[0],(pointer (*)())ROSEUS_ROSWARN);
01340   defun(ctx,"ROS-ERROR",argv[0],(pointer (*)())ROSEUS_ROSERROR);
01341   defun(ctx,"ROS-FATAL",argv[0],(pointer (*)())ROSEUS_ROSFATAL);
01342   defun(ctx,"EXIT",argv[0],(pointer (*)())ROSEUS_EXIT);
01343 
01344   defun(ctx,"SUBSCRIBE",argv[0],(pointer (*)())ROSEUS_SUBSCRIBE);
01345   defun(ctx,"UNSUBSCRIBE",argv[0],(pointer (*)())ROSEUS_UNSUBSCRIBE);
01346   defun(ctx,"GET-NUM-PUBLISHERS",argv[0],(pointer (*)())ROSEUS_GETNUMPUBLISHERS);
01347   defun(ctx,"GET-TOPIC-SUBSCRIBER",argv[0],(pointer (*)())ROSEUS_GETTOPICSUBSCRIBER);
01348 
01349   defun(ctx,"ADVERTISE",argv[0],(pointer (*)())ROSEUS_ADVERTISE);
01350   defun(ctx,"UNADVERTISE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE);
01351   defun(ctx,"PUBLISH",argv[0],(pointer (*)())ROSEUS_PUBLISH);
01352   defun(ctx,"GET-NUM-SUBSCRIBERS",argv[0],(pointer (*)())ROSEUS_GETNUMSUBSCRIBERS);
01353   defun(ctx,"GET-TOPIC-PUBLISHER",argv[0],(pointer (*)())ROSEUS_GETTOPICPUBLISHER);
01354 
01355   defun(ctx,"WAIT-FOR-SERVICE",argv[0],(pointer (*)())ROSEUS_WAIT_FOR_SERVICE);
01356   defun(ctx,"SERVICE-EXISTS", argv[0], (pointer (*)())ROSEUS_SERVICE_EXISTS);
01357   defun(ctx,"SERVICE-CALL",argv[0],(pointer (*)())ROSEUS_SERVICE_CALL);
01358   defun(ctx,"ADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_ADVERTISE_SERVICE);
01359   defun(ctx,"UNADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE_SERVICE);
01360 
01361   defun(ctx,"SET-PARAM",argv[0],(pointer (*)())ROSEUS_SET_PARAM);
01362   defun(ctx,"GET-PARAM",argv[0],(pointer (*)())ROSEUS_GET_PARAM);
01363   defun(ctx,"GET-PARAM-CASHED",argv[0],(pointer (*)())ROSEUS_GET_PARAM_CASHED);
01364   defun(ctx,"HAS-PARAM",argv[0],(pointer (*)())ROSEUS_HAS_PARAM);
01365 
01366   defun(ctx,"ROSPACK-FIND",argv[0],(pointer (*)())ROSEUS_ROSPACK_FIND);
01367   defun(ctx,"RESOLVE-NAME",argv[0],(pointer (*)())ROSEUS_RESOLVE_NAME);
01368   defun(ctx,"GET-NAME",argv[0],(pointer (*)())ROSEUS_GETNAME);
01369   defun(ctx,"GET-NAMESPACE",argv[0],(pointer (*)())ROSEUS_GETNAMESPACE);
01370 
01371   defun(ctx,"ROSEUS-RAW",argv[0],(pointer (*)())ROSEUS);
01372   defun(ctx,"CREATE-NODEHANDLE", argv[0], (pointer (*)())ROSEUS_CREATE_NODEHANDLE);
01373 
01374   pointer_update(Spevalof(PACKAGE),p);
01375 
01376   pointer l;
01377   l=makestring(SVNVERSION,strlen(SVNVERSION));
01378   vpush(l);
01379   l=stacknlist(ctx,1);
01380   QSVNVERSION=defvar(ctx, "ROSEUS-SVNVERSION", l, rospkg);
01381 
01382   M_string remappings;
01383   pointer argp = speval(intern(ctx,"*EUSTOP-ARGUMENT*", strlen("*EUSTOP-ARGUMENT*"),lisppkg));
01384   while(argp!=NIL) {
01385     std::string arg = string((char *)(ccar(argp)->c.str.chars));
01386     // copy from roscpp/src/init.cpp : 432
01387     size_t pos = arg.find(":=");
01388     if (pos != std::string::npos) {
01389       std::string local_name = arg.substr(0, pos);
01390       std::string external_name = arg.substr(pos + 2);
01391       remappings[local_name] = external_name;
01392     }
01393     argp=ccdr(argp);
01394   }
01395   ros::master::init(remappings);
01396   //ros::param::init(remappings);
01397 
01398   return 0;
01399 }
01400 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


roseus
Author(s): Kei Okada (k-okada@jsk.t.u-tokyo.ac.jp)
autogenerated on Sat Mar 23 2013 14:37:36