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


roseus
Author(s): Kei Okada
autogenerated on Wed Apr 3 2019 02:46:38