roseus.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 // author: Kei Okada
36 
37 
38 #include <stdio.h>
39 #include <stdlib.h>
40 #include <unistd.h>
41 #include <string.h>
42 #include <signal.h>
43 #include <math.h>
44 #include <time.h>
45 #include <pthread.h>
46 #include <setjmp.h>
47 #include <errno.h>
48 
49 #include <list>
50 #include <vector>
51 #include <set>
52 #include <string>
53 #include <map>
54 #include <sstream>
55 
56 #include <cstdio>
57 #include <boost/thread/mutex.hpp>
58 #include <boost/thread/condition.hpp>
59 #include <boost/shared_ptr.hpp>
60 #include <boost/algorithm/string.hpp>
61 #include <boost/variant.hpp>
62 #include <boost/foreach.hpp>
63 
64 #include <ros/init.h>
65 #include <ros/time.h>
66 #include <ros/rate.h>
67 #include <ros/master.h>
68 #include <ros/this_node.h>
69 #include <ros/node_handle.h>
70 #include <ros/service.h>
72 #include <ros/service_manager.h>
73 #include <ros/connection.h>
74 #include <rospack/rospack.h>
75 #include <ros/param.h>
76 #include <ros/callback_queue.h>
77 
78 // for eus.h
79 #define class eus_class
80 #define throw eus_throw
81 #define export eus_export
82 #define vector eus_vector
83 #define string eus_string
84 
85 #include "eus.h"
86 extern "C" {
87 #ifdef ROSPACK_EXPORT
89 #else
91 #endif
92  pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env);
94  char modname[] = "___roseus";
95  return add_module_initializer(modname, (pointer (*)())___roseus);}
96  /* get_string is originally defined in lisp/c/makes.c, but it is also defined in Python.so linked from rospack.so
97  to avoid confusion, we have to explictly re-define this method, specially for OSX */
98  byte *get_string(register pointer s){
99  if (isstring(s)) return(s->c.str.chars);
100  if (issymbol(s)) return(s->c.sym.pname->c.str.chars);
101  else error(E_NOSTRING); return NULL; }
102 }
103 
104 #undef class
105 #undef throw
106 #undef export
107 #undef vector
108 #undef string
109 
110 namespace ros {
111  namespace master {
113  void init(const M_string& remappings);
114  }
115  namespace param {
116  void init(const M_string& remappings);
117  }
118 }
119 
120 using namespace ros;
121 using namespace std;
122 
123 #define isInstalledCheck \
124  if( ! ros::ok() ) { error(E_USER,"You must call (ros::roseus \"name\") before creating the first NodeHandle"); }
125 
127 {
128 public:
131  }
134  map<string, boost::shared_ptr<Publisher> > mapAdvertised;
135  map<string, boost::shared_ptr<Subscriber> > mapSubscribed;
136  map<string, boost::shared_ptr<ServiceServer> > mapServiced;
137  map<string, Timer > mapTimered;
138 
139  map<string, boost::shared_ptr<NodeHandle> > mapHandle;
140 };
141 
143 static bool s_bInstalled = false;
144 #define s_node s_staticdata.node
145 #define s_rate s_staticdata.rate
146 #define s_mapAdvertised s_staticdata.mapAdvertised
147 #define s_mapSubscribed s_staticdata.mapSubscribed
148 #define s_mapServiced s_staticdata.mapServiced
149 #define s_mapTimered s_staticdata.mapTimered
150 #define s_mapHandle s_staticdata.mapHandle
151 
153 extern pointer LAMCLOSURE;
154 
155 /***********************************************************
156  * Message wrapper
157  ************************************************************/
158 
159 string getString(pointer message, pointer method) {
160  context *ctx = current_ctx;
161  pointer r, curclass;
162  if ((pointer)findmethod(ctx,method,classof(message),&curclass)!=NIL) {
163  r = csend(ctx,message,method,0);
164  } else if ((pointer)findmethod(ctx,K_ROSEUS_GET,classof(message),&curclass) != NIL ) {
165  r = csend(ctx,message,K_ROSEUS_GET,1,method);
166  } else {
167  r = NULL;
168 #ifdef x86_64
169  ROS_ERROR("could not find method %s for pointer %lx",
170  get_string(method), (long unsigned int)message);
171 #else
172  ROS_ERROR("could not find method %s for pointer %x",
173  get_string(method), (unsigned int)message);
174 #endif
175  }
176  if ( !isstring(r) ) {
177  pointer dest=(pointer)mkstream(ctx,K_OUT,makebuffer(64));
178  prinx(ctx,message,dest);
179  pointer str = makestring((char *)dest->c.stream.buffer->c.str.chars,
180  intval(dest->c.stream.count));
181  ROS_ERROR("send %s to %s returns nil", get_string(method), get_string(str));
182  }
183  ROS_ASSERT(isstring(r));
184  string ret = (char *)get_string(r);
185  return ret;
186 }
187 
188 int getInteger(pointer message, pointer method) {
189  context *ctx = current_ctx;
190  pointer a,curclass;
191  vpush(message);
192  a = (pointer)findmethod(ctx,method,classof(message),&curclass);
193  if (a!=NIL) {
194  pointer r = csend(ctx,message,method,0);
195  vpop(); // message
196  return (ckintval(r));
197  } else {
198 #ifdef x86_64
199  ROS_ERROR("could not find method %s for pointer %lx",
200  get_string(method), (long unsigned int)message);
201 #else
202  ROS_ERROR("could not find method %s for pointer %x",
203  get_string(method), (unsigned int)message);
204 #endif
205  vpop(); // message
206  }
207  return 0;
208 }
209 
211 {
212 public:
215 
216  EuslispMessage(pointer message) : _message(message) {
217  }
219  context *ctx = current_ctx;
220  if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
221  if ( isclass(r._message) ) {
222  //ROS_ASSERT(isclass(r._message));
223  vpush(r._message);
224  _message = makeobject(r._message);
225  vpush(_message);
226  csend(ctx,_message,K_ROSEUS_INIT,0);
227  vpop(); // _message
228  vpop(); // r._message
229  } else {
230  ROS_WARN("r._message must be class");prinx(ctx,r._message,ERROUT);flushstream(ERROUT);terpri(ERROUT);
231  _message = r._message;
232  }
233  }
234  virtual ~EuslispMessage() { }
235 
236  virtual void replaceContents (pointer newMessage) {
237  _message = newMessage;
238  }
239 
240  virtual const string __getDataType() const {
241  return getString(_message, K_ROSEUS_DATATYPE);
242  }
243  virtual const string __getMD5Sum() const {
244  return getString(_message, K_ROSEUS_MD5SUM);
245  }
246  virtual const string __getMessageDefinition() const {
247  return getString(_message, K_ROSEUS_DEFINITION);
248  }
249  virtual const string __getServiceDataType() const {
250  return getString(_message, K_ROSEUS_DATATYPE);
251  }
252  virtual const string __getServerMD5Sum() const {
253  return getString(_message, K_ROSEUS_MD5SUM);
254  }
255 
256  uint32_t serializationLength() const {
257  context *ctx = current_ctx;
258  if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
259  pointer a,curclass;
260  a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(_message),&curclass);
261  ROS_ASSERT(a!=NIL);
262  return getInteger(_message, K_ROSEUS_SERIALIZATION_LENGTH);
263  }
264 
265  virtual uint8_t *serialize(uint8_t *writePtr, uint32_t seqid) const
266  {
267  context *ctx = current_ctx;
268  if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
269  pointer a,curclass;
270  vpush(_message); // to avoid GC
271  uint32_t len = serializationLength();
272  vpop(); // pop _message
273  a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZE,classof(_message),&curclass);
274  ROS_ASSERT(a!=NIL);
275  pointer r = csend(ctx,_message,K_ROSEUS_SERIALIZE,0);
276  ROS_ASSERT(isstring(r));
277  memcpy(writePtr, get_string(r), len);
278  //ROS_INFO("serialize");
279 
280  return writePtr + len;
281  }
282 
283  virtual uint8_t *deserialize(uint8_t *readPtr, uint32_t sz)
284  {
285  context *ctx = current_ctx;
286  if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
287  pointer a,curclass;
288 
289  if ( sz == 0 ) {
290  ROS_DEBUG("empty message!");
291  return readPtr;
292  }
293  vpush(_message);
294  a = (pointer)findmethod(ctx,K_ROSEUS_DESERIALIZE,classof(_message),&curclass);
295  ROS_ASSERT(a!=NIL);
296  pointer p = makestring((char *)readPtr, sz);
297  pointer r;
298  r = csend(ctx,_message,K_ROSEUS_DESERIALIZE,1,p);
299  ROS_ASSERT(r!=NIL);
300  //ROS_INFO("deserialize %d", __serialized_length);
301  vpop(); // pop _message
302 
303  return readPtr + sz;
304  }
305 };
306 
308  if ( eus_msg->_connection_header == NULL ||
309  eus_msg->_connection_header->size() == 0 ) {
310  return;
311  }
312  context *ctx = current_ctx;
313  // store conection headers
314  register pointer ret, header;
315  ret = cons(ctx, NIL, NIL);
316  header = ret;
317  vpush(ret);
318  for(map<string, string>::iterator it = eus_msg->_connection_header->begin(); it != eus_msg->_connection_header->end(); it++){
319  ccdr(ret) = cons(ctx,cons(ctx,makestring((char *)it->first.c_str(), it->first.length()),
320  makestring((char *)it->second.c_str(), it->second.length())),NIL);
321  ret = ccdr(ret);
322  }
323  /* (setslot obj class index newval) */
324  pointer slot_args[4] = {eus_msg->_message, classof(eus_msg->_message), K_ROSEUS_CONNECTION_HEADER, ccdr(header)};
325  SETSLOT(ctx, 4, slot_args);
326  vpop();
327 }
328 
329 namespace ros{
330  namespace serialization{
331 template<> struct Serializer<EuslispMessage> {
332  template<typename Stream>
333  inline static void write(Stream& stream, boost::call_traits<EuslispMessage>::param_type t) {
334  t.serialize(stream.getData(), 0);
335  }
336 
337  template<typename Stream>
338  inline static void read(Stream& stream, boost::call_traits<EuslispMessage>::reference t) {
339  t.deserialize(stream.getData(), stream.getLength());
340  }
341  inline static uint32_t serializedLength(boost::call_traits<EuslispMessage>::param_type t) {
342  return t.serializationLength();
343  }
344 };
345  }
346 }
347 
348 /************************************************************
349  * Subscriptions
350  ************************************************************/
352 public:
353  pointer _scb,_args;
355 
356  EuslispSubscriptionCallbackHelper(pointer scb, pointer args,pointer tmpl) : _args(args), _msg(tmpl) {
357  context *ctx = current_ctx;
358  //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
359  //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
360  if (piscode(scb)) { // compiled code
361  _scb=scb;
362  } else if ((ccar(scb))==LAMCLOSURE) { // uncompiled code
363  if ( ccar(ccdr(scb)) != NIL ) { // function
364  _scb=ccar(ccdr(scb));
365  } else { // lambda function
366  _scb=scb;
367  }
368  } else {
369  ROS_ERROR("subscription callback function install error");
370  }
371  // avoid gc
372  pointer p=gensym(ctx);
373  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));
374  }
376  ROS_ERROR("subscription gc");
377  }
379 #if DEBUG
380  cerr << __PRETTY_FUNCTION__ << endl;
381  cerr << "param.length = " << param.length << endl;
382  cerr << "param.buffer = " << (param.buffer + 4) << endl;
383  cerr << "c_header == " << param.connection_header << endl;
384  for(map<string, string>::iterator it = param.connection_header->begin(); it != param.connection_header->end(); it++){
385  cerr << " " << it->first << " : " << it->second << endl;
386  }
387 #endif
388  ros::VoidConstPtr ptr(new EuslispMessage(_msg));
389  EuslispMessage *eus_msg = (EuslispMessage *)(ptr.get());
390  eus_msg->deserialize(param.buffer, param.length);
391 
392  eus_msg->_connection_header = param.connection_header;
393  return ptr;
394  }
396  EuslispMessage* eus_msg = (EuslispMessage *)((void *)param.event.getConstMessage().get());
397  context *ctx = current_ctx;
398  pointer argp=_args;
399  int argc=0;
400  //ROS_WARN("func");prinx(ctx,_scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
401  //ROS_WARN("argc");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
402  vpush(eus_msg->_message); // to avoid GC
403  if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
404  ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
405  }
406 
407  // store connection header
408  StoreConnectionHeader(eus_msg);
409 
410  while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
411  vpush((pointer)(eus_msg->_message));argc++;
412 
413  ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
414  while(argc-->0)vpop();
415  vpop(); // remove eus_msg._message
416  }
417  virtual const std::type_info& getTypeInfo() {
418  return typeid(EuslispMessage);
419  }
420  virtual bool isConst(){
421  return true;
422  }
423  virtual bool hasHeader(){
424  return true;
425  }
426 };
427 
428 /************************************************************
429  * ServiceCall
430  ************************************************************/
432 public:
433  pointer _scb, _args;
435  string md5, datatype, requestDataType, responseDataType,
436  requestMessageDefinition, responseMessageDefinition;
437 
438  EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass) : _args(args), _req(reqclass), _res(resclass), md5(smd5), datatype(sdatatype) {
439  context *ctx = current_ctx;
440  //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
441  //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
442 
443  if (piscode(scb)) { // compiled code
444  _scb=scb;
445  } else if ((ccar(scb))==LAMCLOSURE) {
446  if ( ccar(ccdr(scb)) != NIL ) { // function
447  _scb=ccar(ccdr(scb));
448  } else { // lambda function
449  _scb=scb;
450  }
451  } else {
452  ROS_ERROR("service callback function install error");
453  }
454  // avoid gc
455  pointer p=gensym(ctx);
456  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));
457 
458  requestDataType = _req.__getDataType();
459  responseDataType = _res.__getDataType();
460  requestMessageDefinition = _req.__getMessageDefinition();
461  responseMessageDefinition = _res.__getMessageDefinition();
462  }
464 
467 
468  virtual std::string getMD5Sum() { return md5; }
469  virtual std::string getDataType() { return datatype; }
470  virtual std::string getRequestDataType() { return requestDataType; }
471  virtual std::string getResponseDataType() { return responseDataType; }
472  virtual std::string getRequestMessageDefinition() { return requestMessageDefinition; }
473  virtual std::string getResponseMessageDefinition() { return responseMessageDefinition; }
474 
476 #if DEBUG
477  cerr << __PRETTY_FUNCTION__ << endl;
478  cerr << "param.length = " << params.request.num_bytes << endl;
479  cerr << "param.buffer = " << (params.request.message_start + 4) << endl;
480  cerr << "c_header == " << params.connection_header << endl;
481  for(map<string, string>::iterator it = params.connection_header->begin(); it != params.connection_header->end(); it++){
482  cerr << " " << it->first << " : " << it->second << endl;
483  }
484 #endif
485  context *ctx = current_ctx;
486  pointer r, argp=_args;
487  int argc=0;
488 
489  vpush(_res._message); // _res._message
490  vpush(_req._message); // _res._message, _req._message
491 
492  if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
493  ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
494  }
495  // Deserialization
496  EuslispMessage eus_msg(_req);
497  vpush(eus_msg._message); // _res._message, _req._message, eus_msg._message
498  eus_msg.deserialize(params.request.message_start, params.request.num_bytes);
499 
500  // store connection header
501  eus_msg._connection_header = params.connection_header;
502  StoreConnectionHeader(&eus_msg);
503 
504  while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
505  vpush((pointer) eus_msg._message);argc++;
506 
507  r = ufuncall(ctx, (ctx->callfp?ctx->callfp->form:NIL),
508  _scb, (pointer)(ctx->vsp-argc),
509  NULL, argc);
510  while(argc-->0)vpop();// _res._message, _req._message, eus_msg._message
511  vpush(r); // _res._message, _req._message, eus_msg._message, r,
512  // Serializaion
513  EuslispMessage eus_res(_res);
514  eus_res.replaceContents(r);
515  // check return value is valid
516  pointer ret_serialize_method, ret_class;
517  if (ispointer(r)) {
518  ret_serialize_method = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(r),&ret_class); }
519  if (!ispointer(r) || ret_serialize_method == NIL) {
520  ROS_ERROR("you may not return valid value in service callback");
521  vpop(); // _res._message, _req._message, eus_msg._message, r
522  vpop(); // _res._message, _req._message, eus_msg._message
523  vpop(); // _res._message, _req._message,
524  vpop(); // _res._message
525  return false;
526  }
527  vpush(eus_res._message); // _res._message, _req._message, eus_msg._message, r, eus_res._message
528  uint32_t serialized_length = eus_res.serializationLength();
529  params.response.num_bytes = serialized_length + 5; // add 5 bytes of message header
530  params.response.buf.reset (new uint8_t[params.response.num_bytes]);
531  params.response.message_start = 0;
532 
533  // SerializedResponseMessage
534  uint8_t *tmp = params.response.buf.get();
535  *tmp++ = 1; // 1 byte of success services flag, now always set true
536  *tmp++ = (uint8_t)((serialized_length >> 0) & 0xFF); // 4bytes of message length
537  *tmp++ = (uint8_t)((serialized_length >> 8) & 0xFF);
538  *tmp++ = (uint8_t)((serialized_length >> 16) & 0xFF);
539  *tmp++ = (uint8_t)((serialized_length >> 24) & 0xFF);
540  eus_res.serialize(tmp, 0);
541  // store connection header
542  eus_res._connection_header = params.connection_header;
543  StoreConnectionHeader(&eus_res);
544 #if DEBUG
545  cerr << "num bytes = " << params.response.num_bytes << endl;
546  ROS_INFO("message_start = %X",params.response.message_start);
547  ROS_INFO("message_ptr = %X",params.response.buf.get());
548  tmp = params.response.buf.get();
549  for(int i=0;i<params.response.num_bytes;i++){
550  ROS_INFO("%X", tmp[i]);
551  }
552 #endif
553  vpop(); // _res._message, _req._message, eus_msg._message, r, eus_res._message
554  vpop(); // _res._message, _req._message, eus_msg._message, r
555  vpop(); // _res._message, _req._message, eus_msg._message
556  vpop(); // _res._message, _req._message,
557  vpop(); // _res._message
558  return true;
559  }
560 };
561 
562 void roseusSignalHandler(int sig)
563 {
564  // memoize for euslisp handler...
565  context *ctx=euscontexts[thr_self()];
566  ctx->intsig = sig;
567 }
568 
569 /************************************************************
570  * EUSLISP functions
571  ************************************************************/
572 pointer ROSEUS(register context *ctx,int n,pointer *argv)
573 {
574  char name[256] = "";
575  uint32_t options = 0;
576  int cargc = 0;
577  char *cargv[32];
578 
579  if( s_bInstalled ) {
580  ROS_WARN("ROSEUS is already installed as %s", ros::this_node::getName().c_str());
581  return (T);
582  }
583 
584  ckarg(3);
585  if (isstring(argv[0]))
586  strncpy(name,(char *)(argv[0]->c.str.chars),255);
587  else error(E_NOSTRING);
588  options = ckintval(argv[1]);
589  pointer p = argv[2];
590  if (islist(p)) {
591  while (1) {
592  if (!iscons(p)) break;
593  cargv[cargc]=(char *)((ccar(p))->c.str.chars);
594  cargc++;
595  p=ccdr(p);
596  }
597  } else error(E_NOSEQ);
598 
599  // convert invalid node name charactors to _, we assume it is '-'
600  for (unsigned int i=0; i < strlen(name); i++)
601  if ( ! (isalpha(name[i]) || isdigit(name[i])) ) name[i] = '_';
602 
603  K_ROSEUS_MD5SUM = defkeyword(ctx,"MD5SUM-");
604  K_ROSEUS_DATATYPE = defkeyword(ctx,"DATATYPE-");
605  K_ROSEUS_DEFINITION = defkeyword(ctx,"DEFINITION-");
606  K_ROSEUS_CONNECTION_HEADER = intern(ctx,"_CONNECTION-HEADER",18,findpkg(makestring("ROS",3)));
607  K_ROSEUS_SERIALIZATION_LENGTH = defkeyword(ctx,"SERIALIZATION-LENGTH");
608  K_ROSEUS_SERIALIZE = defkeyword(ctx,"SERIALIZE");
609  K_ROSEUS_DESERIALIZE = defkeyword(ctx,"DESERIALIZE");
610  K_ROSEUS_GET = defkeyword(ctx,"GET");
611  K_ROSEUS_INIT = defkeyword(ctx,"INIT");
612  K_ROSEUS_REQUEST = defkeyword(ctx,"REQUEST");
613  K_ROSEUS_RESPONSE = defkeyword(ctx,"RESPONSE");
614  K_ROSEUS_GROUPNAME = defkeyword(ctx,"GROUPNAME");
615  K_ROSEUS_ONESHOT = defkeyword(ctx,"ONESHOT");
616  K_ROSEUS_LAST_EXPECTED = defkeyword(ctx,"LAST-EXPECTED");
617  K_ROSEUS_LAST_REAL = defkeyword(ctx,"LAST-REAL");
618  K_ROSEUS_CURRENT_EXPECTED = defkeyword(ctx,"CURRENT-EXPECTED");
619  K_ROSEUS_CURRENT_REAL = defkeyword(ctx,"CURRENT-REAL");
620  K_ROSEUS_LAST_DURATION = defkeyword(ctx,"LAST-DURATION");
621  K_ROSEUS_SEC = defkeyword(ctx,"SEC");
622  K_ROSEUS_NSEC = defkeyword(ctx,"NSEC");
623 
624  s_mapAdvertised.clear();
625  s_mapSubscribed.clear();
626  s_mapServiced.clear();
627  s_mapTimered.clear();
628  s_mapHandle.clear();
629 
630  /*
631  set locale to none to let C RTL assume logging string can contain non-ascii characters.
632  Refer: https://logging.apache.org/log4cxx/latest_stable/faq.html
633  */
634  setlocale(LC_ALL, "");
635 
636  /*
637  force to flag ros::init_options::NoSigintHandler.
638  In fact, this code make no sence, because we steals
639  SIGINT handler by the following `signal'.
640  */
642 
643  /*
644  clear ros::master::g_uri which is defined in ros::master::init in __roseus.
645  this occurs if user set unix::setenv("ROS_MASTER_URI") between __roseus and
646  ROSEUS.
647  */
648  if (!ros::master::g_uri.empty()) {
649  if ( ros::master::g_uri != getenv("ROS_MASTER_URI") ) {
650  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"));
651  ros::master::g_uri.clear();
652  }
653  }
654  try {
655  ros::init(cargc, cargv, name, options);
656  } catch (const ros::InvalidNameException &e) {
657  ROS_ERROR("%s",e.what());
659  return(NIL);
660  }
661 
662  s_node.reset(new ros::NodeHandle());
663  s_rate.reset(new ros::Rate(50));
664 
665  s_bInstalled = true;
666 
667  // install signal handler for sigint. DO NOT call unix:signal after
668  // ros::roseus
669  signal(SIGINT, roseusSignalHandler);
670  return (T);
671 }
672 
674 {
676  string groupname;
677  string ns;
678 
679  ckarg2(1, 2);
680  // ;; arguments ;;
681  // groupname [ namespace ]
682 
683  if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
684  else error(E_NOSTRING);
685  if ( n > 1 ) {
686  if(isstring(argv[1])) ns.assign((char *)get_string(argv[1]));
687  else error(E_NOSTRING);
688  }
689 
690  if( s_mapHandle.find(groupname) != s_mapHandle.end() ) {
691  ROS_DEBUG("groupname %s is already used", groupname.c_str());
692  return (NIL);
693  }
694 
696  if ( n > 1 ) {
698  s_mapHandle[groupname] = hd;
699  } else {
701  s_mapHandle[groupname] = hd;
702  }
703  //add callbackqueue to hd
704  hd->setCallbackQueue( new CallbackQueue() );
705 
706  return (T);
707 }
708 
710 {
712  while (ctx->intsig==0 && ros::ok()) {
713  ros::spinOnce();
714  s_rate->sleep();
715  }
716  return (NIL);
717 }
718 
720 {
722  ckarg2(0, 1);
723  // ;; arguments ;;
724  // [ groupname ]
725 
726  if ( n > 0 ) {
727  string groupname;
728  if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
729  else error(E_NOSTRING);
730 
731  map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
732  if( it == s_mapHandle.end() ) {
733  ROS_ERROR("Groupname %s is missing", groupname.c_str());
734  return (T);
735  }
736  boost::shared_ptr<NodeHandle > hdl = (it->second);
737  // spin this nodehandle
738  ((CallbackQueue *)hdl->getCallbackQueue())->callAvailable();
739 
740  return (NIL);
741  } else {
742  ros::spinOnce();
743  return (NIL);
744  }
745 }
746 
748 {
750  pointer timevec;
752 
753  timevec=makevector(C_INTVECTOR,2);
754  vpush(timevec);
755  timevec->c.ivec.iv[0]=t.sec;
756  timevec->c.ivec.iv[1]=t.nsec;
757  vpop();
758  return (timevec);
759 }
760 
762 {
764  numunion nu;
765  ckarg(1);
766  float timeout=ckfltval(argv[0]);
767  s_rate.reset(new ros::Rate(timeout));
768  return(T);
769 }
770 
772 {
774  s_rate->sleep();
775  return (T);
776 }
777 
779 {
781  numunion nu;
782  ckarg(1);
783  float sleep=ckfltval(argv[0]);
784  ros::Duration(sleep).sleep();
785  return(T);
786 }
787 
788 pointer ROSEUS_OK(register context *ctx,int n,pointer *argv)
789 {
790  if (ros::ok()) {
791  return (T);
792  } else {
793  return (NIL);
794  }
795 }
796 
797 
798 #define def_rosconsole_formatter(funcname, rosfuncname) \
799  pointer funcname(register context *ctx,int n,pointer *argv) \
800  { pointer *argv2,msg; \
801  int argc2; \
802  argc2 = n+1; \
803  argv2 = (pointer *)malloc(sizeof(pointer)*argc2); \
804  argv2[0] = NIL; \
805  for(int i=0;i<n;i++) argv2[i+1]=argv[i] ; \
806  msg = XFORMAT(ctx, argc2, argv2); \
807  rosfuncname("%s", msg->c.str.chars); \
808  free(argv2); \
809  return (T); \
810  }
811 
812 def_rosconsole_formatter(ROSEUS_ROSDEBUG, ROS_DEBUG)
813 def_rosconsole_formatter(ROSEUS_ROSINFO, ROS_INFO)
814 def_rosconsole_formatter(ROSEUS_ROSWARN, ROS_WARN)
815 def_rosconsole_formatter(ROSEUS_ROSERROR, ROS_ERROR)
816 def_rosconsole_formatter(ROSEUS_ROSFATAL, ROS_FATAL)
817 
818 pointer ROSEUS_EXIT(register context *ctx,int n,pointer *argv)
819 {
820  ROS_INFO("%s", __PRETTY_FUNCTION__);
821  if( s_bInstalled ) {
822  ROS_INFO("exiting roseus %ld", (n==0)?n:ckintval(argv[0]));
823  s_mapAdvertised.clear();
824  s_mapSubscribed.clear();
825  s_mapServiced.clear();
826  s_mapTimered.clear();
827  s_mapHandle.clear();
828  ros::shutdown();
829  }
830  if (n==0) _exit(0);
831  else _exit(ckintval(argv[0]));
832 }
833 
834 /************************************************************
835  * ROSEUS Publisher/Subscriber
836  ************************************************************/
837 pointer ROSEUS_SUBSCRIBE(register context *ctx,int n,pointer *argv)
838 {
840  string topicname;
841  pointer message, fncallback, args;
842  int queuesize = 1;
843  NodeHandle *lnode = s_node.get();
844 
845  // ;; arguments ;;
846  // topicname message_type callbackfunc args0 ... argsN [ queuesize ] [ :groupname groupname ]
847  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
848  else error(E_NOSTRING);
849 
850  if (n > 1 && issymbol(argv[n-2]) && isstring(argv[n-1])) {
851  if (argv[n-2] == K_ROSEUS_GROUPNAME) {
852  string groupname;
853  groupname.assign((char *)get_string(argv[n-1]));
854  map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
855  if( it != s_mapHandle.end() ) {
856  ROS_DEBUG("subscribe with groupname=%s", groupname.c_str());
857  lnode = (it->second).get();
858  } else {
859  ROS_ERROR("Groupname %s is missing. Topic %s is not subscribed. Call (ros::create-nodehandle \"%s\") first.",
860  groupname.c_str(), topicname.c_str(), groupname.c_str());
861  return (NIL);
862  }
863  n -= 2;
864  }
865  }
866  if (isint(argv[n-1])) {queuesize = ckintval(argv[n-1]);n--;}
867  ROS_DEBUG("subscribe %s queuesize=%d", topicname.c_str(), queuesize);
868  // TODO:need error checking
869  message = argv[1];
870  fncallback = argv[2];
871  args=NIL;
872  for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
873 
874  EuslispMessage msg(message);
877  (new EuslispSubscriptionCallbackHelper(fncallback, args, message)));
878  SubscribeOptions so(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType());
879  so.helper = *callback;
880  Subscriber subscriber = lnode->subscribe(so);
882  if ( !!sub ) {
883  s_mapSubscribed[topicname] = sub;
884  } else {
885  ROS_ERROR("s_mapSubscribed");
886  }
887 
888  return (T);
889 }
890 
891 pointer ROSEUS_UNSUBSCRIBE(register context *ctx,int n,pointer *argv)
892 {
893  string topicname;
894 
895  ckarg(1);
896  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
897  else error(E_NOSTRING);
898 
899  bool bSuccess = s_mapSubscribed.erase(topicname)>0;
900 
901  return (bSuccess?T:NIL);
902 }
903 
904 pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx,int n,pointer *argv)
905 {
906  string topicname;
907  int ret;
908 
909  ckarg(1);
910  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
911  else error(E_NOSTRING);
912 
913  bool bSuccess = false;
914  map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
915  if( it != s_mapSubscribed.end() ) {
916  boost::shared_ptr<Subscriber> subscriber = (it->second);
917  ret = subscriber->getNumPublishers();
918  bSuccess = true;
919  }
920 
921  return (bSuccess?(makeint(ret)):NIL);
922 }
923 
925 {
926  string topicname;
927  string ret;
928 
929  ckarg(1);
930  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
931  else error(E_NOSTRING);
932 
933  bool bSuccess = false;
934  map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
935  if( it != s_mapSubscribed.end() ) {
936  boost::shared_ptr<Subscriber> subscriber = (it->second);
937  ret = subscriber->getTopic();
938  bSuccess = true;
939  }
940 
941  return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
942 }
943 
944 pointer ROSEUS_ADVERTISE(register context *ctx,int n,pointer *argv)
945 {
947  string topicname;
948  pointer message;
949  int queuesize = 1;
950  bool latch = false;
951 
952  ckarg2(2,4);
953  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
954  else error(E_NOSTRING);
955 
956  message = argv[1];
957  if ( n > 2 ) {
958  queuesize = ckintval(argv[2]);
959  }
960  if ( n > 3 ) {
961  latch = (argv[3]!=NIL ? true : false);
962  }
963  ROS_DEBUG("advertise %s %d %d", topicname.c_str(), queuesize, latch);
964  if( s_mapAdvertised.find(topicname) != s_mapAdvertised.end() ) {
965  ROS_WARN("topic %s already advertised", topicname.c_str());
966  return (NIL);
967  }
968 
969  EuslispMessage msg(message);
970  AdvertiseOptions ao(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType(), msg.__getMessageDefinition());
971  ao.latch = latch;
972  Publisher publisher = s_node->advertise(ao);
974  if ( !!pub ) {
975  s_mapAdvertised[topicname] = pub;
976  } else {
977  ROS_ERROR("s_mapAdvertised");
978  }
979 
980  return (T);
981 }
982 
983 pointer ROSEUS_UNADVERTISE(register context *ctx,int n,pointer *argv)
984 {
985  string topicname;
986 
987  ckarg(1);
988  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
989  else error(E_NOSTRING);
990 
991  bool bSuccess = s_mapAdvertised.erase(topicname)>0;
992 
993  return (bSuccess?T:NIL);
994 }
995 
996 pointer ROSEUS_PUBLISH(register context *ctx,int n,pointer *argv)
997 {
999  string topicname;
1000  pointer emessage;
1001 
1002  ckarg(2);
1003  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
1004  else error(E_NOSTRING);
1005 
1006  emessage = argv[1];
1007 
1008  bool bSuccess = false;
1009  map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
1010  if( it != s_mapAdvertised.end() ) {
1011  boost::shared_ptr<Publisher> publisher = (it->second);
1012  EuslispMessage message(emessage);
1013  publisher->publish(message);
1014  bSuccess = true;
1015  }
1016 
1017  if ( ! bSuccess ) {
1018  ROS_ERROR("attempted to publish to topic %s, which was not " \
1019  "previously advertised. call (ros::advertise \"%s\") first.",
1020  topicname.c_str(), topicname.c_str());
1021  }
1022 
1023  return (T);
1024 }
1025 
1027 {
1028  string topicname;
1029  int ret;
1030 
1031  ckarg(1);
1032  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
1033  else error(E_NOSTRING);
1034 
1035  bool bSuccess = false;
1036  map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
1037  if( it != s_mapAdvertised.end() ) {
1038  boost::shared_ptr<Publisher> publisher = (it->second);
1039  ret = publisher->getNumSubscribers();
1040  bSuccess = true;
1041  }
1042 
1043  if ( ! bSuccess ) {
1044  ROS_ERROR("attempted to getNumSubscribers to topic %s, which was not " \
1045  "previously advertised. call (ros::advertise \"%s\") first.",
1046  topicname.c_str(), topicname.c_str());
1047  }
1048 
1049  return (bSuccess?(makeint(ret)):NIL);
1050 }
1051 
1053 {
1054  string topicname;
1055  string ret;
1056 
1057  ckarg(1);
1058  if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
1059  else error(E_NOSTRING);
1060 
1061  bool bSuccess = false;
1062  map<string, boost::shared_ptr<Publisher> >::iterator it = s_mapAdvertised.find(topicname);
1063  if( it != s_mapAdvertised.end() ) {
1064  boost::shared_ptr<Publisher> publisher = (it->second);
1065  ret = publisher->getTopic();
1066  bSuccess = true;
1067  }
1068 
1069  return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
1070 }
1071 
1072 /************************************************************
1073  * ROSEUS ServiceCall
1074  ************************************************************/
1076 {
1078  string service;
1079 
1080  ckarg2(1,2);
1081  if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
1082  else error(E_NOSTRING);
1083 
1084  int32_t timeout = -1;
1085 
1086  if( n > 1 )
1087  timeout = (int32_t)ckintval(argv[1]);
1088 
1089  bool bSuccess = service::waitForService(service, ros::Duration(timeout));
1090 
1091  return (bSuccess?T:NIL);
1092 }
1093 
1094 pointer ROSEUS_SERVICE_EXISTS(register context *ctx,int n,pointer *argv)
1095 {
1097  string service;
1098 
1099  ckarg(1);
1100  if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
1101  else error(E_NOSTRING);
1102 
1103  bool bSuccess = service::exists(service, true);
1104 
1105  return (bSuccess?T:NIL);
1106 }
1107 
1108 pointer ROSEUS_SERVICE_CALL(register context *ctx,int n,pointer *argv)
1109 {
1111  string service;
1112  pointer emessage;
1113  bool persist = false;
1114  ckarg2(2,3);
1115  if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
1116  else error(E_NOSTRING);
1117  emessage = argv[1];
1118  if ( n > 2 ) {
1119  persist = (argv[2] != NIL ? true : false);
1120  }
1121  static std::map<std::string, ros::ServiceServerLinkPtr> service_link_cache;
1122  static std::map<std::string, std::string> service_md5_cache;
1123  EuslispMessage request(emessage);
1124  vpush(request._message); // to avoid GC, it may not be required...
1125  EuslispMessage response(csend(ctx,emessage,K_ROSEUS_RESPONSE,0));
1126  vpush(response._message); // to avoid GC, its important
1127 
1128  // NOTE: To make use of connection header, ServiceServerLink is manually handled instead of just invoking ServiceClient.call.
1129  // ServiceClientOptions sco(service, request.__getMD5Sum(), persist, M_string());
1130  // client = s_node->serviceClient(sco);
1131  // bool bSuccess = client.call(request, response, request.__getMD5Sum());
1133  if (persist) {
1134  if ( service_link_cache.find(service) != service_link_cache.end() &&
1135  ( ! service_link_cache[service]->isValid() ||
1136  service_md5_cache[service] !=request.__getMD5Sum() )) {
1137  service_link_cache[service]->getConnection()->drop(ros::Connection::Destructing);
1138  service_link_cache[service].reset();
1139  service_link_cache.erase(service);
1140  service_md5_cache.erase(service);
1141  }
1142 
1143  if (service_link_cache.find(service) == service_link_cache.end()) {
1144  service_link_cache[service] = ros::ServiceManager::instance()->createServiceServerLink(service, persist, request.__getMD5Sum(), request.__getMD5Sum(), M_string());
1145  service_md5_cache[service] = request.__getMD5Sum();
1146  }
1147  link = service_link_cache[service];
1148  } else {
1149  link = ros::ServiceManager::instance()->createServiceServerLink(service, persist, request.__getMD5Sum(), request.__getMD5Sum(), M_string());
1150  }
1151 
1152  bool bSuccess = true;
1154  ros::SerializedMessage ser_resp;
1155  if (link && link->isValid()) {
1156  bSuccess = link->call(ser_req, ser_resp);
1157  if ( bSuccess ) {
1158  try {
1159  ros::serialization::deserializeMessage(ser_resp, response);
1160  } catch (std::exception& e) {
1161  ROS_ERROR("Exception thrown while deserializing service call: %s", e.what());
1162  bSuccess = false;
1163  }
1164  boost::shared_ptr<map<string, string> >connection_header = link->getConnection()->getHeader().getValues();
1165 #if DEBUG
1166  cerr << __PRETTY_FUNCTION__ << endl;
1167  cerr << "c_header == " << connection_header << endl;
1168  for(map<string, string>::iterator it = connection_header->begin(); it != connection_header->end(); it++){
1169  cerr << " " << it->first << " : " << it->second << endl;
1170  }
1171 #endif
1172  response._connection_header = connection_header;
1173  StoreConnectionHeader(&response);
1174  link.reset();
1175  // If we're shutting down but the node haven't finished yet, wait until we do
1176  while (ros::isShuttingDown() && ros::ok()) {
1177  ros::WallDuration(0.001).sleep();
1178  }
1179  }
1180  } else {
1181  bSuccess = false;
1182  ROS_ERROR("Failed to establish connection to service server");
1183  }
1184  vpop(); // pop response._message
1185  vpop(); // pop request._message
1186  if ( ! bSuccess ) {
1187  ROS_ERROR("attempted to call service %s, but failed ",
1188  ros::names::resolve(service).c_str());
1189  }
1190 
1191  return (response._message);
1192 }
1193 
1195 {
1197  string service;
1198  pointer emessage;
1199  pointer fncallback, args;
1200 
1201  if (isstring(argv[0])) service = ros::names::resolve((char *)get_string(argv[0]));
1202  else error(E_NOSTRING);
1203  emessage = argv[1];
1204  fncallback = argv[2];
1205  args=NIL;
1206  for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
1207  if( s_mapServiced.find(service) != s_mapServiced.end() ) {
1208  ROS_INFO("service %s already advertised", service.c_str());
1209  return (NIL);
1210  }
1211 
1212  EuslispMessage message(emessage);
1213  vpush(message._message); // to avoid GC in csend
1214  pointer request(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_REQUEST));
1215  pointer response(csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_RESPONSE));
1216  vpop(); // pop message._message
1219  (new EuslispServiceCallbackHelper(fncallback, args, message.__getMD5Sum(),
1220  message.__getDataType(), request, response)));
1222  aso.service.assign(service);
1223  aso.datatype = (*callback->get()).getDataType();
1224  aso.md5sum = (*callback->get()).getMD5Sum();
1225  aso.req_datatype = (*callback->get()).getRequestDataType();
1226  aso.res_datatype = (*callback->get()).getResponseDataType();
1227  aso.helper = *callback;
1228  ServiceServer server = s_node->advertiseService(aso);
1230  if ( !!ser ) {
1231  s_mapServiced[service] = ser;
1232  } else {
1233  ROS_ERROR("s_mapServiced");
1234  }
1235 
1236  return (T);
1237 }
1238 
1240 {
1241  string service;
1242 
1243  ckarg(1);
1244  if (isstring(argv[0])) service = ros::names::resolve((char *)(argv[0]));
1245  else error(E_NOSTRING);
1246 
1247  ROS_DEBUG("unadvertise %s", service.c_str());
1248  bool bSuccess = s_mapServiced.erase(service)>0;
1249 
1250  return (bSuccess?T:NIL);
1251 }
1252 
1253 void EusValueToXmlRpc(register context *ctx, pointer argp, XmlRpc::XmlRpcValue& rpc_value)
1254 {
1255  numunion nu;
1256 
1257  if ( islist(argp) && islist(ccar(argp))) { // alist
1258  pointer a;
1259  int j;
1260  // set keys
1261  std::ostringstream stringstream;
1262  stringstream << "<value><struct>";
1263  a = argp;
1264  while(islist(a)){
1265  pointer v = ccar(a);
1266  if ( iscons(v) ) { // is alist
1267  if ( issymbol(ccar(v)) ) {
1268  string skey = string((char *)get_string(ccar(v)->c.sym.pname));
1269  boost::algorithm::to_lower(skey);
1270  stringstream << "<member><name>" << skey << "</name><value><boolean>0</boolean></value></member>";
1271  }else{
1272  ROS_ERROR("ROSEUS_SET_PARAM: EusValueToXmlRpc: assuming symbol");prinx(ctx,ccar(v),ERROUT);flushstream(ERROUT);terpri(ERROUT);
1273  }
1274  }else{
1275  ROS_ERROR("ROSEUS_SET_PARAM: EusValueToXmlRpc: assuming alist");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
1276  }
1277  a=ccdr(a);
1278  }
1279  stringstream << "</struct></value>";
1280  j=0; rpc_value.fromXml(stringstream.str(), &j);
1281  // set values
1282  a = argp;
1283  while(islist(a)){
1284  pointer v = ccar(a);
1285  if ( iscons(v) ) {
1286  if ( issymbol(ccar(v)) ) {
1287  string skey = string((char *)get_string(ccar(v)->c.sym.pname));
1288  boost::algorithm::to_lower(skey);
1290  EusValueToXmlRpc(ctx, ccdr(v), p);
1291  rpc_value[skey] = p;
1292  }
1293  }
1294  a=ccdr(a);
1295  }
1296  } else if ( islist(argp) ) { // list
1297  pointer a;
1298  int i;
1299  // get size
1300  a = argp;
1301  i = 0; while ( islist(a) ) { a=ccdr(a); i++; }
1302  rpc_value.setSize(i);
1303  // fill items
1304  a = argp;
1305  i = 0;
1306  while ( islist(a) ) {
1308  EusValueToXmlRpc(ctx, ccar(a), p);
1309  rpc_value[i] = p;
1310  a=ccdr(a);
1311  i++;
1312  }
1313  } else if ( isstring(argp) ) {
1314  rpc_value = (char *)get_string(argp);
1315  } else if ( isint(argp) ) {
1316  rpc_value = (int)(intval(argp));
1317  } else if ( isflt(argp) ) {
1318  rpc_value = (double)(fltval(argp));
1319  } else if (argp == T) {
1320  rpc_value = XmlRpc::XmlRpcValue((bool)true);
1321  } else if (argp == NIL) {
1322  rpc_value = XmlRpc::XmlRpcValue((bool)false);
1323  } else if ( issymbol(argp) ) {
1324  string s((char *)get_string(argp->c.sym.pname));
1325  boost::algorithm::to_lower(s);
1326  rpc_value = s.c_str();
1327  } else {
1328  ROS_ERROR("EusValueToXmlRpc: unknown parameters");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
1330  }
1331 }
1332 
1333 pointer ROSEUS_SET_PARAM(register context *ctx,int n,pointer *argv)
1334 {
1335  string key;
1336  string s;
1337 
1338  ckarg(2);
1339  if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
1340  else error(E_NOSTRING);
1342  EusValueToXmlRpc(ctx, argv[1], param);
1343  ros::param::set(key,param);
1344 
1345  return (T);
1346 }
1347 
1349 {
1350  numunion nu;
1351  pointer ret, first;
1352 
1353  if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeBoolean ){
1354  if ( rpc_value ) return T; else return NIL;
1355  }
1356  else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeDouble ){
1357  return makeflt((double)rpc_value);
1358  }
1359  else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeInt ){
1360  return makeint((int)rpc_value);
1361  }
1362  else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeString ){
1363  std::string str = rpc_value;
1364  return makestring((char*)str.c_str(), ((std::string)rpc_value).length());
1365  }
1366  else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeArray ){
1367  ret = cons(ctx, NIL, NIL);
1368  first = ret;
1369  vpush(ret);
1370  for ( int i = 0; i < rpc_value.size(); i++){
1371  ccdr(ret) = cons(ctx, XmlRpcToEusValue(ctx, rpc_value[i]), NIL);
1372  ret = ccdr(ret);
1373  }
1374  vpop(); // vpush(ret);
1375  return ccdr(first);
1376  }
1377  else if ( rpc_value.getType() == XmlRpc::XmlRpcValue::TypeStruct ){
1378  ret = cons(ctx, NIL, NIL);
1379  first = ret;
1380  vpush(ret);
1381  XmlRpc::XmlRpcValue::iterator it = rpc_value.begin();
1382  while(it !=rpc_value.end()) {
1383  std::string key = it->first;
1384  pointer tmp = cons(ctx, makestring((char*)key.c_str(), key.length()), NIL);
1385  vpush(tmp);
1386  ccdr(tmp) = XmlRpcToEusValue(ctx, it->second);
1387  ccdr(ret) = cons(ctx, tmp, NIL);
1388  ret = ccdr(ret);
1389  vpop(); // vpush(tmp);
1390  it++;
1391  }
1392  vpop(); // vpush(ret);
1393  return ccdr(first);
1394  } else {
1395  ROS_FATAL("unknown rosparam type!");
1396  return NIL;
1397  }
1398  return NIL;
1399 }
1400 
1402 {
1403  numunion nu;
1404  pointer ret, first;
1405  ret = cons(ctx, NIL, NIL);
1406  first = ret;
1407  vpush(ret);
1408  if ( param_list.getType() == XmlRpc::XmlRpcValue::TypeArray ){
1409  for ( int i = 0; i < param_list.size(); i++){
1410  if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeBoolean ){
1411  if ( param_list[i] ){
1412  ccdr(ret) = cons(ctx, T, NIL);
1413  ret = ccdr(ret);
1414  } else {
1415  ccdr(ret) = cons(ctx, NIL, NIL);
1416  ret = ccdr(ret);
1417  }
1418  }
1419  else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble ){
1420  ccdr(ret) = cons(ctx, makeflt((double)param_list[i]), NIL);
1421  ret = ccdr(ret);
1422  }
1423  else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeInt ){
1424  ccdr(ret) = cons(ctx, makeint((int)param_list[i]), NIL);
1425  ret = ccdr(ret);
1426  }
1427  else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeString ){
1428  std::string str = param_list[i];
1429  ccdr(ret) = cons(ctx, makestring((char*)str.c_str(), ((std::string)param_list[i]).length()), NIL);
1430  ret = ccdr(ret);
1431  }
1432  else if ( param_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct ){
1433  ccdr(ret) = cons(ctx, XmlRpcToEusValue(ctx, param_list[i]), NIL);
1434  ret = ccdr(ret);
1435  }
1436  else {
1437  ROS_FATAL("unknown rosparam type!");
1438  vpop(); // remove vpush(ret)
1439  return NIL;
1440  }
1441  }
1442  vpop(); // remove vpush(ret)
1443  return ccdr(first);
1444  } else if ( param_list.getType() == XmlRpc::XmlRpcValue::TypeStruct ) {
1445  return XmlRpcToEusValue(ctx, param_list);
1446  } else
1447  return (NIL);
1448 }
1449 
1450 pointer ROSEUS_GET_PARAM(register context *ctx,int n,pointer *argv)
1451 {
1452  numunion nu;
1453  string key;
1454 
1455  ckarg2(1,2);
1456  if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
1457  else error(E_NOSTRING);
1458 
1459  string s;
1460  double d;
1461  bool b;
1462  int i;
1463  pointer ret;
1464  XmlRpc::XmlRpcValue param_list;
1465 
1466  if ( ros::param::get(key, s) ) {
1467  ret = makestring((char *)s.c_str(), s.length());
1468  } else if ( ros::param::get(key, d) ) {
1469  ret = makeflt(d);
1470  } else if ( ros::param::get(key, i) ) {
1471  ret = makeint(i);
1472  } else if ( ros::param::get(key, b) ) {
1473  if ( b == true )
1474  ret = T;
1475  else
1476  ret = NIL;
1477  } else if (ros::param::get(key, param_list)){
1478  ret = XmlRpcToEusList(ctx, param_list);
1479  }else {
1480  if ( n == 2 ) {
1481  ret = COPYOBJ(ctx,1,argv+1);
1482  } else {
1483  ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
1484  ret = NIL;
1485  }
1486  }
1487  return (ret);
1488 }
1489 
1491 {
1492  numunion nu;
1493  string key;
1494 
1495  ckarg2(1,2);
1496  if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
1497  else error(E_NOSTRING);
1498 
1499  string s;
1500  double d;
1501  int i;
1502  bool b;
1503  pointer ret;
1504  XmlRpc::XmlRpcValue param_list;
1505  if ( ros::param::getCached(key, s) ) {
1506  ret = makestring((char *)s.c_str(), s.length());
1507  } else if ( ros::param::getCached(key, d) ) {
1508  ret = makeflt(d);
1509  } else if ( ros::param::getCached(key, i) ) {
1510  ret = makeint(i);
1511  } else if ( ros::param::getCached(key, b) ) {
1512  if ( b == true )
1513  ret = T;
1514  else
1515  ret = NIL;
1516  } else if (ros::param::getCached(key, param_list)){
1517  ret = XmlRpcToEusList(ctx, param_list);
1518  } else {
1519  if ( n == 2 ) {
1520  ret = COPYOBJ(ctx,1,argv+1);
1521  } else {
1522  ROS_ERROR("unknown ros::param::get, key=%s", key.c_str());
1523  ret = NIL;
1524  }
1525  }
1526  return (ret);
1527 }
1528 
1529 pointer ROSEUS_HAS_PARAM(register context *ctx,int n,pointer *argv)
1530 {
1531  string key;
1532 
1533  ckarg(1);
1534  if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
1535  else error(E_NOSTRING);
1536 
1537  return((ros::param::has(key))?(T):(NIL));
1538 }
1539 
1540 pointer ROSEUS_DELETE_PARAM(register context *ctx,int n,pointer *argv)
1541 {
1542  string key;
1543 
1544  ckarg(1);
1545  if (isstring(argv[0])) key.assign((char *)get_string(argv[0]));
1546  else error(E_NOSTRING);
1547 
1548  return((ros::param::del(key))?(T):(NIL));
1549 }
1550 
1551 pointer ROSEUS_ROSPACK_FIND(register context *ctx,int n,pointer *argv)
1552 {
1553  ckarg(1);
1554 
1555  string pkg;
1556  if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
1557  else error(E_NOSTRING);
1558 
1559  try {
1560 #ifdef ROSPACK_EXPORT
1561  rospack::Package *p = rp.get_pkg(pkg);
1562  if (p!=NULL) return(makestring((char *)p->path.c_str(),p->path.length()));
1563 #else
1564  std::string path;
1565  if (rp.find(pkg,path)==true) return(makestring((char *)path.c_str(),path.length()));
1566 #endif
1567  } catch (runtime_error &e) {
1568  }
1569  return(NIL);
1570 }
1571 
1572 pointer ROSEUS_ROSPACK_DEPENDS(register context *ctx,int n,pointer *argv)
1573 {
1574  // (ros::rospack-depends package-name)
1575  ckarg(1);
1576 
1577  string pkg;
1578  if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
1579  else error(E_NOSTRING);
1580 
1581  try {
1582  // 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
1583  std::vector<std::string> flags;
1584  std::vector<rospack::Stackage*> stackages;
1585  if(!rp.depsOnDetail(pkg, true, stackages, true))
1586  return (NIL);
1587  //
1588  std::vector<std::string> deps;
1589  if (rp.deps(pkg,false,deps)) {
1590  register pointer ret, first;
1591  ret=cons(ctx, NIL, NIL);
1592  first = ret;
1593  vpush(ret);
1594  for (std::vector<std::string>::iterator it = deps.begin() ; it != deps.end(); it++) {
1595  const std::string& dep = *it;
1596  ccdr(ret) = cons(ctx, makestring((char *)dep.c_str(), dep.length()), NIL);
1597  ret = ccdr(ret);
1598  }
1599  vpop(); // vpush(ret)
1600  return ccdr(first);
1601  }
1602  } catch (runtime_error &e) {
1603  }
1604  return(NIL);
1605 }
1606 
1607 pointer ROSEUS_ROSPACK_PLUGINS(register context *ctx,int n,pointer *argv)
1608 {
1609  // (ros::rospack-plugins package-name attibute-name)
1610  ckarg(2);
1611  string pkg, attrib;
1612  pointer ret, first;
1613  if (isstring(argv[0])) pkg.assign((char *)get_string(argv[0]));
1614  else error(E_NOSTRING);
1615  if (isstring(argv[1])) attrib.assign((char *)get_string(argv[1]));
1616  else error(E_NOSTRING);
1617  try {
1618  std::vector<std::string> flags;
1619  if (rp.plugins(pkg, attrib, "", flags)) {
1620  ret = cons(ctx, NIL, NIL);
1621  first = ret;
1622  vpush(ret);
1623  for (size_t i = 0; i < flags.size(); i++) {
1624  // flags[i] = laser_proc /opt/ros/hydro/share/laser_proc/nodelets.xml
1625  std::vector<std::string> parsed_string;
1626  boost::algorithm::split(parsed_string, flags[i], boost::is_any_of(" "));
1627  std::string package = parsed_string[0];
1628  std::string value = parsed_string[1];
1629  pointer tmp = cons(ctx, cons(ctx,
1630  makestring((char*)package.c_str(), package.length()),
1631  makestring((char*)value.c_str(), value.length())),
1632  NIL);
1633  ccdr(ret) = tmp;
1634  ret = tmp;
1635  }
1636  vpop(); // ret
1637  return ccdr(first);
1638  }
1639  else {
1640  return(NIL);
1641  }
1642  }
1643  catch (runtime_error &e) {
1644  }
1645  return(NIL);
1646 }
1647 
1648 pointer ROSEUS_RESOLVE_NAME(register context *ctx,int n,pointer *argv)
1649 {
1650  ckarg(1);
1651  if (!isstring(argv[0])) error(E_NOSTRING);
1652  std::string src;
1653  src.assign((char *)(argv[0]->c.str.chars));
1654  std::string dst = ros::names::resolve(src);
1655  return(makestring((char *)dst.c_str(), dst.length()));
1656 }
1657 
1658 pointer ROSEUS_GETNAME(register context *ctx,int n,pointer *argv)
1659 {
1660  ckarg(0);
1661  return(makestring((char *)ros::this_node::getName().c_str(),
1663 }
1664 
1665 pointer ROSEUS_GETNAMESPACE(register context *ctx,int n,pointer *argv)
1666 {
1667  ckarg(0);
1668  // https://github.com/ros/ros_comm/pull/1100
1669  // Clean the namespace to get rid of double or trailing forward slashes
1671  return(makestring((char *)ns.c_str(), ns.length()));
1672 }
1673 
1674 pointer ROSEUS_SET_LOGGER_LEVEL(register context *ctx, int n, pointer *argv)
1675 {
1676  ckarg(2);
1677  string logger;
1678  if (isstring(argv[0])) logger.assign((char *)get_string(argv[0]));
1679  else error(E_NOSTRING);
1680  int log_level = intval(argv[1]);
1682  switch(log_level){
1683  case 1:
1685  break;
1686  case 2:
1688  break;
1689  case 3:
1691  break;
1692  case 4:
1694  break;
1695  case 5:
1697  break;
1698  default:
1699  return (NIL);
1700  }
1701 
1702  bool success = ::ros::console::set_logger_level(logger, level);
1703  if (success)
1704  {
1706  return (T);
1707  }
1708  return (NIL);
1709 }
1710 
1711 pointer ROSEUS_GET_HOST(register context *ctx,int n,pointer *argv)
1712 {
1713  ckarg(0);
1714 
1716  return makestring((char*)host.c_str(), host.length());
1717 }
1718 
1719 pointer ROSEUS_GET_NODES(register context *ctx,int n,pointer *argv)
1720 {
1721  ckarg(0);
1722 
1723  ros::V_string nodes;
1724  if ( ! ros::master::getNodes(nodes) ) {
1725  return NIL;
1726  }
1727 
1728  register pointer ret, first;
1729  ret=cons(ctx, NIL, NIL);
1730  first = ret;
1731  vpush(ret);
1732  for (ros::V_string::iterator it = nodes.begin() ; it != nodes.end(); it++) {
1733  std::string node = *it;
1734  ccdr(ret) = cons(ctx, makestring((char *)node.c_str(), node.length()), NIL);
1735  ret = ccdr(ret);
1736  }
1737  vpop(); // vpush(ret)
1738 
1739  return ccdr(first);
1740 }
1741 
1742 pointer ROSEUS_GET_PORT(register context *ctx,int n,pointer *argv)
1743 {
1744  ckarg(0);
1745 
1746  return makeint(ros::master::getPort());
1747 }
1748 
1749 pointer ROSEUS_GET_URI(register context *ctx,int n,pointer *argv)
1750 {
1751  ckarg(0);
1752 
1754  return makestring((char*)uri.c_str(), uri.length());
1755 }
1756 
1757 pointer ROSEUS_GET_TOPICS(register context *ctx,int n,pointer *argv)
1758 {
1759  ckarg(0);
1760 
1761  ros::master::V_TopicInfo topics;
1762  if ( !ros::master::getTopics(topics) ) {
1763  return NIL;
1764  }
1765 
1766  register pointer ret, first;
1767  ret=cons(ctx, NIL, NIL);
1768  first = ret;
1769  vpush(ret);
1770  for (ros::master::V_TopicInfo::iterator it = topics.begin() ; it != topics.end(); it++) {
1771  const ros::master::TopicInfo& info = *it;
1772  pointer tmp = cons(ctx,makestring((char*)info.name.c_str(), info.name.length()), makestring((char*)info.datatype.c_str(), info.datatype.length()));
1773  vpush(tmp);
1774  ccdr(ret) = cons(ctx, tmp, NIL);
1775  ret = ccdr(ret);
1776  vpop(); // vpush(tmp)
1777  }
1778  vpop(); // vpush(ret)
1779 
1780  return ccdr(first);
1781 }
1782 
1784 {
1785  pointer _scb, _args;
1786 public:
1787  TimerFunction(pointer scb, pointer args) : _scb(scb), _args(args) {
1788  //context *ctx = current_ctx;
1789  //ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
1790  //ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
1791  }
1792  void operator()(const ros::TimerEvent& event)
1793  {
1794  context *ctx = current_ctx;
1795  pointer argp=_args;
1796  int argc=0;
1797 
1798  pointer clsptr = NIL;
1799  for(int i=0; i<nextcix;i++) {
1800  if(!memcmp(classtab[i].def->c.cls.name->c.sym.pname->c.str.chars,(char *)"TIMER-EVENT",11)) {
1801  clsptr = classtab[i].def;
1802  }
1803  }
1804  if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
1805  ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
1806  }
1807 
1808  pointer tevent = makeobject(clsptr);
1809  csend(ctx,tevent,K_ROSEUS_INIT,0);
1810  csend(ctx,tevent,K_ROSEUS_LAST_EXPECTED,2,K_ROSEUS_SEC,makeint(event.last_expected.sec));
1811  csend(ctx,tevent,K_ROSEUS_LAST_EXPECTED,2,K_ROSEUS_NSEC,makeint(event.last_expected.nsec));
1812  csend(ctx,tevent,K_ROSEUS_LAST_REAL,2,K_ROSEUS_SEC,makeint(event.last_real.sec));
1813  csend(ctx,tevent,K_ROSEUS_LAST_REAL,2,K_ROSEUS_NSEC,makeint(event.last_real.nsec));
1814  csend(ctx,tevent,K_ROSEUS_CURRENT_EXPECTED,2,K_ROSEUS_SEC,makeint(event.current_expected.sec));
1815  csend(ctx,tevent,K_ROSEUS_CURRENT_EXPECTED,2,K_ROSEUS_NSEC,makeint(event.current_expected.nsec));
1816  csend(ctx,tevent,K_ROSEUS_CURRENT_REAL,2,K_ROSEUS_SEC,makeint(event.current_real.sec));
1817  csend(ctx,tevent,K_ROSEUS_CURRENT_REAL,2,K_ROSEUS_NSEC,makeint(event.current_real.nsec));
1818  csend(ctx,tevent,K_ROSEUS_LAST_DURATION,2,K_ROSEUS_SEC,makeint(event.profile.last_duration.sec));
1819  csend(ctx,tevent,K_ROSEUS_LAST_DURATION,2,K_ROSEUS_NSEC,makeint(event.profile.last_duration.nsec));
1820 
1821  while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
1822  vpush((pointer)(tevent));argc++;
1823 
1824  ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
1825  while(argc-->0)vpop();
1826 
1827  }
1828 };
1829 
1830 pointer ROSEUS_CREATE_TIMER(register context *ctx,int n,pointer *argv)
1831 {
1833  numunion nu;
1834  bool oneshot = false;
1835  pointer fncallback = NIL, args;
1836  NodeHandle *lnode = s_node.get();
1837  string fncallname;
1838  float period=ckfltval(argv[0]);
1839 
1840  // period callbackfunc args0 ... argsN [ oneshot ]
1841  // ;; oneshot ;;
1842  if (n > 1 && issymbol(argv[n-2]) && issymbol(argv[n-1])) {
1843  if (argv[n-2] == K_ROSEUS_ONESHOT) {
1844  if ( argv[n-1] != NIL ) {
1845  oneshot = true;
1846  }
1847  n -= 2;
1848  }
1849  }
1850  // ;; functions ;;
1851  if (piscode(argv[1])) { // compiled code
1852  fncallback=argv[1];
1853  std::ostringstream stringstream;
1854  stringstream << reinterpret_cast<long>(argv[2]) << " ";
1855  for (int i=3; i<n;i++)
1856  stringstream << string((char*)(argv[i]->c.sym.pname->c.str.chars)) << " ";
1857  fncallname = stringstream.str();
1858  } else if ((ccar(argv[1]))==LAMCLOSURE) { // uncompiled code
1859  if ( ccar(ccdr(argv[1])) != NIL ) { // function
1860  fncallback=ccar(ccdr(argv[1]));
1861  fncallname = string((char*)(fncallback->c.sym.pname->c.str.chars));
1862  } else { // lambda function
1863  fncallback=argv[1];
1864  std::ostringstream stringstream;
1865  stringstream << reinterpret_cast<long>(argv[1]);
1866  fncallname = stringstream.str();
1867  }
1868  } else {
1869  ROS_ERROR("subscription callback function install error");
1870  }
1871 
1872  // ;; arguments ;;
1873  args=NIL;
1874  for (int i=n-1;i>=2;i--) args=cons(ctx,argv[i],args);
1875 
1876  // avoid gc
1877  pointer p=gensym(ctx);
1878  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));
1879 
1880  // ;; store mapTimered
1881  ROS_DEBUG("create timer %s at %f (oneshot=%d)", fncallname.c_str(), period, oneshot);
1882  s_mapTimered[fncallname] = lnode->createTimer(ros::Duration(period), TimerFunction(fncallback, args), oneshot);
1883 
1884  return (T);
1885 }
1886 
1887 /************************************************************
1888  * __roseus
1889  ************************************************************/
1891 #include "defun.h"
1892 pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
1893 {
1894 #ifdef ROSPACK_EXPORT
1895 #else
1896  std::vector<std::string> search_path;
1897  rp.getSearchPathFromEnv(search_path);
1898  rp.crawl(search_path, 1);
1899 #endif
1900 
1901  pointer rospkg,p=Spevalof(PACKAGE);
1902  rospkg=findpkg(makestring("ROS",3));
1903  if (rospkg == 0) rospkg=makepkg(ctx,makestring("ROS", 3),NIL,NIL);
1904  Spevalof(PACKAGE)=rospkg;
1905 
1906  QANON=defvar(ctx,"*ANONYMOUS-NAME*",makeint(ros::init_options::AnonymousName),rospkg);
1907  QNOOUT=defvar(ctx,"*NO-ROSOUT*",makeint(ros::init_options::NoRosout),rospkg);
1908  QROSDEBUG=defvar(ctx,"*ROSDEBUG*",makeint(1),rospkg);
1909  QROSINFO=defvar(ctx,"*ROSINFO*",makeint(2),rospkg);
1910  QROSWARN=defvar(ctx,"*ROSWARN*",makeint(3),rospkg);
1911  QROSERROR=defvar(ctx,"*ROSERROR*",makeint(4),rospkg);
1912  QROSFATAL=defvar(ctx,"*ROSFATAL*",makeint(5),rospkg);
1913  defun(ctx,"SPIN",argv[0],(pointer (*)())ROSEUS_SPIN, "Enter simple event loop");
1914 
1915  defun(ctx,"SPIN-ONCE",argv[0],(pointer (*)())ROSEUS_SPINONCE,
1916  "&optional groupname ;; spin only group\n\n"
1917  "Process a single round of callbacks.\n");
1918  defun(ctx,"TIME-NOW-RAW",argv[0],(pointer (*)())ROSEUS_TIME_NOW, "");
1919  defun(ctx,"RATE",argv[0],(pointer (*)())ROSEUS_RATE, "frequency\n\n" "Construct ros timer for periodic sleeps");
1920  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.");
1921  defun(ctx,"DURATION-SLEEP",argv[0],(pointer (*)())ROSEUS_DURATION_SLEEP, "second\n\nSleeps for amount of the time specified by this duration.");
1922  defun(ctx,"OK",argv[0],(pointer (*)())ROSEUS_OK, "Check whether it's time to exit. ");
1923 
1924  defun(ctx,"ROS-DEBUG",argv[0],(pointer (*)())ROSEUS_ROSDEBUG,
1925  "write mesage to debug output\n"
1926  "\n"
1927  " (ros::ros-debug \"this is error ~A\" 0)\n");
1928  defun(ctx,"ROS-INFO",argv[0],(pointer (*)())ROSEUS_ROSINFO, "write mesage to info output");
1929  defun(ctx,"ROS-WARN",argv[0],(pointer (*)())ROSEUS_ROSWARN, "write mesage to warn output");
1930  defun(ctx,"ROS-ERROR",argv[0],(pointer (*)())ROSEUS_ROSERROR, "write mesage to error output");
1931  defun(ctx,"ROS-FATAL",argv[0],(pointer (*)())ROSEUS_ROSFATAL, "write mesage to fatal output");
1932  defun(ctx,"EXIT",argv[0],(pointer (*)())ROSEUS_EXIT, "Exit ros clinet");
1933 
1934  defun(ctx,"SUBSCRIBE",argv[0],(pointer (*)())ROSEUS_SUBSCRIBE,
1935  "topicname message_type callbackfunc args0 ... argsN &optional (queuesize 1) %key (:groupname groupname)\n\n"
1936  "Subscribe to a topic, version for class member function with bare pointer.\n"
1937  "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"
1938  "\n"
1939  "This version of subscribe is a convenience function for using function, member function, lmabda function:\n"
1940  " ;; callback function\n"
1941  " (defun string-cb (msg) (print (list 'cb (sys::thread-self) (send msg :data))))\n"
1942  " (ros::subscribe \"chatter\" std_msgs::string #'string-cb)\n"
1943  " ;; lambda function\n"
1944  " (ros::subscribe \"chatter\" std_msgs::string\n"
1945  " #'(lambda (msg) (ros::ros-info\n"
1946  " (format nil \"I heard ~A\" (send msg :data)))))\n"
1947  " ;; method call\n"
1948  " (defclass string-cb-class\n"
1949  " :super propertied-object\n"
1950  " :slots ())\n"
1951  " (defmethod string-cb-class\n"
1952  " (:init () (ros::subscribe \"chatter\" std_msgs::string #'send self :string-cb))\n"
1953  " (:string-cb (msg) (print (list 'cb self (send msg :data)))))\n"
1954  " (setq m (instance string-cb-class :init))\n"
1955  );
1956  defun(ctx,"UNSUBSCRIBE",argv[0],(pointer (*)())ROSEUS_UNSUBSCRIBE, "topicname\n\n""Unsubscribe topic");
1957  defun(ctx,"GET-NUM-PUBLISHERS",argv[0],(pointer (*)())ROSEUS_GETNUMPUBLISHERS, "Returns the number of publishers this subscriber is connected to. ");
1958  defun(ctx,"GET-TOPIC-SUBSCRIBER",argv[0],(pointer (*)())ROSEUS_GETTOPICSUBSCRIBER, "topicname\n\n""Retuns the name of topic if it already subscribed");
1959  defun(ctx,"ADVERTISE",argv[0],(pointer (*)())ROSEUS_ADVERTISE,
1960  "topic message_class &optional (queuesize 1) (latch nil)\n"
1961  "Advertise a topic.\n"
1962  "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"
1963  " (ros::advertise \"chatter\" std_msgs::string 1)");
1964  defun(ctx,"UNADVERTISE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE, "Unadvertise topic");
1965  defun(ctx,"PUBLISH",argv[0],(pointer (*)())ROSEUS_PUBLISH,
1966  "topic message\n\n"
1967  "Publish a message on the topic\n"
1968  " (ros::roseus \"talker\")\n"
1969  " (ros::advertise \"chatter\" std_msgs::string 1)\n"
1970  " (ros::rate 100)\n"
1971  " (while (ros::ok)\n"
1972  " (setq msg (instance std_msgs::string :init))\n"
1973  " (send msg :data (format nil \"hello world ~a\" (send (ros::time-now) :sec-nsec)))\n"
1974  " (ros::publish \"chatter\" msg)\n"
1975  " (ros::sleep))\n");
1976  defun(ctx,"GET-NUM-SUBSCRIBERS",argv[0],(pointer (*)())ROSEUS_GETNUMSUBSCRIBERS, "Retuns number of subscribers this publish is connected to");
1977  defun(ctx,"GET-TOPIC-PUBLISHER",argv[0],(pointer (*)())ROSEUS_GETTOPICPUBLISHER, "topicname\n\n""Retuns the name of topic if it already published");
1978 
1979  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.");
1980  defun(ctx,"SERVICE-EXISTS", argv[0], (pointer (*)())ROSEUS_SERVICE_EXISTS, "servicename\n\n""Checks if a service is both advertised and available.");
1981  defun(ctx,"SERVICE-CALL",argv[0],(pointer (*)())ROSEUS_SERVICE_CALL,
1982  "servicename message_type &optional persist\n\n"
1983  "Invoke RPC service\n"
1984  " (ros::roseus \"add_two_ints_client\")\n"
1985  " (ros::wait-for-service \"add_two_ints\")\n"
1986  " (setq req (instance roseus::AddTwoIntsRequest :init))\n"
1987  " (send req :a (random 10))\n"
1988  " (send req :b (random 20))\n"
1989  " (setq res (ros::service-call \"add_two_ints\" req t))\n"
1990  " (format t \"~d + ~d = ~d~~%\" (send req :a) (send req :b) (send res :sum))\n");
1991  defun(ctx,"ADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_ADVERTISE_SERVICE,
1992  "servicename message_type callback function\n\n"
1993  "Advertise a service\n"
1994  " (ros::advertise-service \"add_two_ints\" roseus::AddTwoInts #'add-two-ints)");
1995  defun(ctx,"UNADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE_SERVICE, "Unadvertise service");
1996 
1997  defun(ctx,"SET-PARAM",argv[0],(pointer (*)())ROSEUS_SET_PARAM, "key value\n\n""Set parameter");
1998  defun(ctx,"GET-PARAM",argv[0],(pointer (*)())ROSEUS_GET_PARAM, "key\n\n""Get parameter");
1999  defun(ctx,"GET-PARAM-CACHED",argv[0],(pointer (*)())ROSEUS_GET_PARAM_CACHED, "Get chached parameter");
2000  defun(ctx,"HAS-PARAM",argv[0],(pointer (*)())ROSEUS_HAS_PARAM, "Check whether a parameter exists on the parameter server.");
2001  defun(ctx,"DELETE-PARAM",argv[0],(pointer (*)())ROSEUS_DELETE_PARAM, "key\n\n""Delete parameter from server");
2002 
2003  defun(ctx,"ROSPACK-FIND",argv[0],(pointer (*)())ROSEUS_ROSPACK_FIND, "Returns ros package path");
2004  defun(ctx,"ROSPACK-PLUGINS",argv[0],(pointer (*)())ROSEUS_ROSPACK_PLUGINS, "Returns plugins of ros packages");
2005  defun(ctx,"ROSPACK-DEPENDS",argv[0],(pointer (*)())ROSEUS_ROSPACK_DEPENDS, "Returns ros package dependencies list");
2006  defun(ctx,"RESOLVE-NAME",argv[0],(pointer (*)())ROSEUS_RESOLVE_NAME, "Returns ros resolved name");
2007  defun(ctx,"GET-NAME",argv[0],(pointer (*)())ROSEUS_GETNAME, "Returns current node name");
2008  defun(ctx,"GET-NAMESPACE",argv[0],(pointer (*)())ROSEUS_GETNAMESPACE, "Returns current node name space");
2009 
2010  defun(ctx,"ROSEUS-RAW",argv[0],(pointer (*)())ROSEUS, "");
2011  defun(ctx,"CREATE-NODEHANDLE", argv[0], (pointer (*)())ROSEUS_CREATE_NODEHANDLE, "groupname &optional namespace ;;\n\n"
2012  "Create ros NodeHandle with given group name. \n"
2013  "\n"
2014  " (ros::roseus \"test\")\n"
2015  " (ros::create-node-handle \"mygroup\")\n"
2016  " (ros::subscribe \"/test\" std_msgs::String #'(lambda (m) (print m)) :groupname \"mygroup\")\n"
2017  " (while (ros::ok) (ros::spin-once \"mygroup\"))\n");
2018  defun(ctx,"SET-LOGGER-LEVEL",argv[0],(pointer (*)())ROSEUS_SET_LOGGER_LEVEL, "");
2019 
2020  defun(ctx,"GET-HOST",argv[0],(pointer (*)())ROSEUS_GET_HOST, "Get the hostname where the master runs.");
2021  defun(ctx,"GET-NODES",argv[0],(pointer (*)())ROSEUS_GET_NODES, "Retreives the currently-known list of nodes from the master.");
2022  defun(ctx,"GET-PORT",argv[0],(pointer (*)())ROSEUS_GET_PORT, "Get the port where the master runs.");
2023  defun(ctx,"GET-URI",argv[0],(pointer (*)())ROSEUS_GET_URI, "Get the full URI to the master ");
2024  defun(ctx,"GET-TOPICS",argv[0],(pointer (*)())ROSEUS_GET_TOPICS, "Get the list of topics that are being published by all nodes.");
2025 
2026  defun(ctx,"CREATE-TIMER",argv[0],(pointer (*)())ROSEUS_CREATE_TIMER, "Create periodic callbacks.");
2027 
2028  pointer_update(Spevalof(PACKAGE),p);
2029 
2030  pointer l;
2031  l=makestring(REPOVERSION,strlen(REPOVERSION));
2032  vpush(l);
2033  l=stacknlist(ctx,1);
2034  QREPOVERSION=defvar(ctx, "ROSEUS-REPO-VERSION", l, rospkg);
2035 
2036  M_string remappings;
2037  pointer argp = speval(intern(ctx,"*EUSTOP-ARGUMENT*", strlen("*EUSTOP-ARGUMENT*"),lisppkg));
2038  while(argp!=NIL) {
2039  std::string arg = string((char *)(ccar(argp)->c.str.chars));
2040  // copy from roscpp/src/init.cpp : 432
2041  size_t pos = arg.find(":=");
2042  if (pos != std::string::npos) {
2043  std::string local_name = arg.substr(0, pos);
2044  std::string external_name = arg.substr(pos + 2);
2045  remappings[local_name] = external_name;
2046  }
2047  argp=ccdr(argp);
2048  }
2049  ros::master::init(remappings);
2050  //ros::param::init(remappings);
2051 
2052  return 0;
2053 }
2054 
pointer QROSDEBUG
Definition: roseus.cpp:152
context * euscontexts[MAXTHREAD]
d
pointer prinx(context *, pointer, pointer)
map< string, boost::shared_ptr< ServiceServer > > mapServiced
subscribed topics
Definition: roseus.cpp:136
pointer ROSEUS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:572
static bool s_bInstalled
Definition: roseus.cpp:143
ROSCPP_DECL uint32_t getPort()
rospack::Rospack rp
Definition: roseus.cpp:90
pointer ROSEUS_WAIT_FOR_SERVICE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1075
int nextcix
int getInteger(pointer message, pointer method)
Definition: roseus.cpp:188
pointer intern(context *, char *, int, pointer)
ROSCPP_DECL const std::string & getURI()
pointer makeint(eusinteger_t v)
bool param(const std::string &param_name, T &param_val, const T &default_val)
pointer K_ROSEUS_RESPONSE
Definition: roseus.cpp:152
#define ROS_FATAL(...)
EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass)
Definition: roseus.cpp:438
#define s_rate
Definition: roseus.cpp:145
pointer ROSEUS_UNADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1239
static RoseusStaticData s_staticdata
Definition: roseus.cpp:142
static void read(Stream &stream, boost::call_traits< EuslispMessage >::reference t)
Definition: roseus.cpp:338
WallDuration last_duration
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
virtual const string __getDataType() const
Definition: roseus.cpp:240
pointer K_OUT
ValueStruct::iterator iterator
pointer ROSEUS_SERVICE_CALL(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1108
virtual std::string getDataType()
Definition: roseus.cpp:469
bool depsOnDetail(const std::string &name, bool direct, std::vector< Stackage * > &deps, bool ignore_missing=false)
struct string str
void operator()(const ros::TimerEvent &event)
Definition: roseus.cpp:1792
byte chars[1]
pointer QROSFATAL
Definition: roseus.cpp:152
pointer * vsp
pointer COPYOBJ(context *, int, pointer *)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define s_mapSubscribed
Definition: roseus.cpp:147
static uint32_t serializedLength(boost::call_traits< EuslispMessage >::param_type t)
Definition: roseus.cpp:341
pointer T
pointer findmethod(context *, pointer, pointer, pointer *)
int size() const
pointer ROSEUS_TIME_NOW(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:747
pointer ROSEUS_GET_NODES(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1719
virtual void replaceContents(pointer newMessage)
Definition: roseus.cpp:236
pointer QROSWARN
Definition: roseus.cpp:152
void init(const M_string &remappings)
pointer ROSEUS_SPIN(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:709
bool sleep() const
boost::shared_ptr< M_string > connection_header
pointer makepkg(context *, pointer, pointer, pointer)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
pointer ROSEUS_RESOLVE_NAME(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1648
pointer defkeyword(context *, char *)
void register_roseus()
Definition: roseus.cpp:93
pointer K_ROSEUS_SERIALIZE
Definition: roseus.cpp:152
virtual std::string getResponseMessageDefinition()
Definition: roseus.cpp:473
pointer SETSLOT(context *, int, pointer *)
virtual const string __getMessageDefinition() const
Definition: roseus.cpp:246
pointer K_ROSEUS_CONNECTION_HEADER
Definition: roseus.cpp:152
ROSCPP_DECL const std::string & getName()
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
std::string g_uri
void EusValueToXmlRpc(register context *ctx, pointer argp, XmlRpc::XmlRpcValue &rpc_value)
Definition: roseus.cpp:1253
void deserializeMessage(const SerializedMessage &m, M &message)
struct ros::TimerEvent::@0 profile
pointer K_ROSEUS_DESERIALIZE
Definition: roseus.cpp:152
pointer ROSEUS_UNADVERTISE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:983
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
EuslispMessage(pointer message)
Definition: roseus.cpp:216
uint32_t serializationLength() const
Definition: roseus.cpp:256
pointer ufuncall(context *, pointer, pointer, pointer, struct bindframe *, int)
ROSCPP_DECL std::string clean(const std::string &name)
pointer ROSEUS_GET_PARAM(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1450
#define s_mapAdvertised
Definition: roseus.cpp:146
bool deps(const std::string &name, bool direct, std::vector< std::string > &deps)
ROS_INFO ROS_ERROR int n
Definition: roseus.cpp:818
pointer ROSEUS_DELETE_PARAM(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1540
virtual const std::type_info & getTypeInfo()
Definition: roseus.cpp:417
Type const & getType() const
std::vector< TopicInfo > V_TopicInfo
pointer ROSEUS_ROSPACK_PLUGINS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1607
server
virtual ~EuslispMessage()
Definition: roseus.cpp:234
#define ROS_WARN(...)
pointer makevector(pointer, int)
pointer LAMCLOSURE
struct symbol sym
pointer QNOOUT
Definition: roseus.cpp:152
ckarg(2)
void add_module_initializer(char *, pointer(*)())
float ckfltval()
pointer K_ROSEUS_INIT
Definition: roseus.cpp:152
int intsig
pointer K_ROSEUS_ONESHOT
Definition: roseus.cpp:152
static const ServiceManagerPtr & instance()
pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:924
pointer mkstream(context *, pointer, pointer)
#define s_mapTimered
Definition: roseus.cpp:149
pointer XmlRpcToEusValue(register context *ctx, XmlRpc::XmlRpcValue rpc_value)
Definition: roseus.cpp:1348
pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:904
pointer ROSEUS_OK(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:788
struct intvector ivec
TimerFunction(pointer scb, pointer args)
Definition: roseus.cpp:1787
std::map< std::string, std::string > M_string
virtual std::string getMD5Sum()
Definition: roseus.cpp:468
virtual const string __getServiceDataType() const
Definition: roseus.cpp:249
union cell::cellunion c
const boost::shared_ptr< ConstMessage > & getConstMessage() const
pointer _scb
Definition: roseus.cpp:1785
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
ROS_INFO ROS_ERROR int pointer * argv
Definition: roseus.cpp:819
std::vector< std::string > V_string
pointer ROSEUS_GET_PARAM_CACHED(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1490
SubscriptionCallbackHelperPtr helper
pointer QROSINFO
Definition: roseus.cpp:152
bool sleep() const
E_NOSTRING
ServiceCallbackHelperPtr helper
struct stream stream
ROSCPP_DECL const std::string & getNamespace()
pointer ROSEUS_ADVERTISE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:944
long l
pointer setval(context *, pointer, pointer)
pointer K_ROSEUS_MD5SUM
Definition: roseus.cpp:152
void setSize(int size)
virtual bool call(ros::ServiceCallbackHelperCallParams &params)
Definition: roseus.cpp:475
ROSCPP_DECL bool get(const std::string &key, std::string &s)
pointer ROSEUS_ROSPACK_DEPENDS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1572
#define ROS_INFO(...)
options
pointer defvar(context *, char *, pointer, pointer)
pointer ROSEUS_SET_LOGGER_LEVEL(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1674
pointer K_ROSEUS_CURRENT_EXPECTED
Definition: roseus.cpp:152
#define s_mapHandle
Definition: roseus.cpp:150
pointer ROSEUS_GET_TOPICS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1757
struct callframe * callfp
EuslispSubscriptionCallbackHelper(pointer scb, pointer args, pointer tmpl)
Definition: roseus.cpp:356
pointer form
pointer ROSEUS_SERVICE_EXISTS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1094
ROSCPP_DECL bool ok()
boost::shared_ptr< M_string > connection_header
short s
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
pointer K_ROSEUS_DATATYPE
Definition: roseus.cpp:152
#define s_mapServiced
Definition: roseus.cpp:148
#define string
Definition: roseus.cpp:83
pointer K_ROSEUS_CURRENT_REAL
Definition: roseus.cpp:152
pointer buffer
ROSCPP_DECL bool isShuttingDown()
pointer K_ROSEUS_GROUPNAME
Definition: roseus.cpp:152
pointer makebuffer(int)
virtual const string __getServerMD5Sum() const
Definition: roseus.cpp:252
#define isInstalledCheck
Definition: roseus.cpp:123
virtual const string __getMD5Sum() const
Definition: roseus.cpp:243
pointer QANON
Definition: roseus.cpp:152
pointer lisppkg
ROSCPP_DECL bool has(const std::string &key)
void StoreConnectionHeader(EuslispMessage *eus_msg)
Definition: roseus.cpp:307
SerializedMessage serializeMessage(const M &message)
#define s_node
Definition: roseus.cpp:144
pointer ROSEUS_HAS_PARAM(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1529
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
virtual boost::shared_ptr< EuslispMessage > createResponse()
Definition: roseus.cpp:466
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
EuslispMessage(const EuslispMessage &r)
Definition: roseus.cpp:218
string getString(pointer message, pointer method)
Definition: roseus.cpp:159
pointer K_ROSEUS_REQUEST
Definition: roseus.cpp:152
ROSCPP_DECL const std::string & getHost()
bool getSearchPathFromEnv(std::vector< std::string > &sp)
bool fromXml(std::string const &valueXml, int *offset)
void roseusSignalHandler(int sig)
Definition: roseus.cpp:562
virtual boost::shared_ptr< EuslispMessage > createRequest()
Definition: roseus.cpp:465
pointer defun(context *, char *, pointer, pointer(*)(), char *)
pointer PACKAGE
map< string, boost::shared_ptr< Publisher > > mapAdvertised
advertised topics
Definition: roseus.cpp:134
int flushstream(pointer)
pointer _message
Definition: roseus.cpp:213
virtual void call(ros::SubscriptionCallbackHelperCallParams &param)
Definition: roseus.cpp:395
virtual uint8_t * deserialize(uint8_t *readPtr, uint32_t sz)
Definition: roseus.cpp:283
pointer stacknlist(context *, int)
E_NOSEQ
boost::shared_ptr< ros::NodeHandle > node
Definition: roseus.cpp:132
ROSCPP_DECL bool del(const std::string &key)
pointer ROSEUS_CREATE_TIMER(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1830
pointer K_ROSEUS_LAST_DURATION
Definition: roseus.cpp:152
float fltval()
pointer K_ROSEUS_GET
Definition: roseus.cpp:152
long iv[1]
pointer ROSEUS_SUBSCRIBE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:837
pointer ROSEUS_SLEEP(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:771
pointer ROSEUS_GETNAME(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1658
void terpri(pointer)
void crawl(std::vector< std::string > search_path, bool force)
virtual uint8_t * serialize(uint8_t *writePtr, uint32_t seqid) const
Definition: roseus.cpp:265
pointer makestring(char *, int)
boost::shared_array< uint8_t > buf
pointer ROSEUS_GETTOPICPUBLISHER(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1052
else _exit(ckintval(argv[0]))
#define NULL
pointer C_INTVECTOR
pointer pname
pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:673
map< string, boost::shared_ptr< Subscriber > > mapSubscribed
subscribed topics
Definition: roseus.cpp:135
pointer csend(va_alist)
bool find(const std::string &name, std::string &path)
pointer XmlRpcToEusList(register context *ctx, XmlRpc::XmlRpcValue param_list)
Definition: roseus.cpp:1401
pointer ROSEUS_GETNAMESPACE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1665
GLfloat v[8][3]
static Time now()
pointer count
pointer ROSEUS_GET_PORT(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1742
ROSCPP_DECL void shutdown()
pointer ROSEUS_SET_PARAM(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1333
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
E_MISMATCHARG
const std::string header
pointer findpkg()
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
pointer K_ROSEUS_LAST_REAL
Definition: roseus.cpp:152
pointer makeobject(pointer)
ROSCPP_DECL bool getNodes(V_string &nodes)
unsigned char byte
virtual std::string getRequestMessageDefinition()
Definition: roseus.cpp:472
pointer QREPOVERSION
Definition: roseus.cpp:152
unsigned int thr_self()
pointer ROSEUS_GET_HOST(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1711
eusinteger_t intval(pointer p)
virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams &param)
Definition: roseus.cpp:378
#define ROS_ASSERT(cond)
pointer def
MessageEvent< void const > event
bool plugins(const std::string &name, const std::string &attrib, const std::string &top, std::vector< std::string > &flags)
struct class_desc classtab[MAXCLASS]
pointer ROSEUS_DURATION_SLEEP(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:778
pointer ROSEUS_SPINONCE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:719
ROSCPP_DECL void spinOnce()
virtual std::string getRequestDataType()
Definition: roseus.cpp:470
pointer NIL
boost::shared_ptr< ros::Rate > rate
Definition: roseus.cpp:133
pointer ROSEUS_ADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1194
pointer K_FUNCTION_DOCUMENTATION
#define ROS_ERROR(...)
pointer K_ROSEUS_NSEC
Definition: roseus.cpp:152
pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
Definition: roseus.cpp:1892
pointer K_ROSEUS_SEC
Definition: roseus.cpp:152
pointer ERROUT
boost::shared_ptr< map< string, string > > _connection_header
Definition: roseus.cpp:214
static void write(Stream &stream, boost::call_traits< EuslispMessage >::param_type t)
Definition: roseus.cpp:333
pointer ROSEUS_PUBLISH(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:996
pointer K_ROSEUS_SERIALIZATION_LENGTH
Definition: roseus.cpp:152
pointer K_ROSEUS_DEFINITION
Definition: roseus.cpp:152
pointer gensym(context *)
pointer ROSEUS_GET_URI(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1749
pointer ROSEUS_GETNUMSUBSCRIBERS(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1026
byte * get_string(register pointer s)
Definition: roseus.cpp:98
const std::string response
map< string, Timer > mapTimered
subscribed timers
Definition: roseus.cpp:137
char a[26]
pointer length
pointer QROSERROR
Definition: roseus.cpp:152
virtual std::string getResponseDataType()
Definition: roseus.cpp:471
pointer K_ROSEUS_LAST_EXPECTED
Definition: roseus.cpp:152
map< string, boost::shared_ptr< NodeHandle > > mapHandle
for grouping nodehandle
Definition: roseus.cpp:139
#define def_rosconsole_formatter(funcname, rosfuncname)
Definition: roseus.cpp:798
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
pointer ROSEUS_RATE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:761
pointer ROSEUS_UNSUBSCRIBE(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:891
pointer makeflt()
pointer ROSEUS_ROSPACK_FIND(register context *ctx, int n, pointer *argv)
Definition: roseus.cpp:1551
#define ROS_DEBUG(...)


roseus
Author(s): Kei Okada
autogenerated on Thu Apr 4 2019 02:55:35