-
Notifications
You must be signed in to change notification settings - Fork 56
/
roseus.cpp
2094 lines (1864 loc) · 72.2 KB
/
roseus.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
// author: Kei Okada
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <string.h>
#include <signal.h>
#include <math.h>
#include <time.h>
#include <pthread.h>
#include <setjmp.h>
#include <errno.h>
#include <list>
#include <vector>
#include <set>
#include <string>
#include <map>
#include <sstream>
#include <cstdio>
#include <boost/thread/mutex.hpp>
#include <boost/thread/condition.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/algorithm/string.hpp>
#include <boost/variant.hpp>
#include <boost/foreach.hpp>
#include <ros/init.h>
#include <ros/time.h>
#include <ros/rate.h>
#include <ros/master.h>
#include <ros/this_node.h>
#include <ros/node_handle.h>
#include <ros/service.h>
#include <ros/service_server_link.h>
#include <ros/service_manager.h>
#include <ros/connection.h>
#include <rospack/rospack.h>
#include <ros/param.h>
#include <ros/callback_queue.h>
// for eus.h
#define class eus_class
#define throw eus_throw
#define export eus_export
#define vector eus_vector
#define string eus_string
#include "eus.h"
extern "C" {
#ifdef ROSPACK_EXPORT
rospack::ROSPack rp;
#else
rospack::Rospack rp;
#endif
pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env);
void register_roseus(){
char modname[] = "___roseus";
return add_module_initializer(modname, (pointer (*)())___roseus);}
/* get_string is originally defined in lisp/c/makes.c, but it is also defined in Python.so linked from rospack.so
to avoid confusion, we have to explictly re-define this method, specially for OSX */
byte *get_string(register pointer s){
if (isstring(s)) return(s->c.str.chars);
if (issymbol(s)) return(s->c.sym.pname->c.str.chars);
else error(E_NOSTRING); return NULL; }
}
#undef class
#undef throw
#undef export
#undef vector
#undef string
namespace ros {
namespace master {
std::string g_uri;
void init(const M_string& remappings);
}
namespace param {
void init(const M_string& remappings);
}
}
using namespace ros;
using namespace std;
#define isInstalledCheck \
if( ! ros::ok() ) { error(E_USER,"You must call (ros::roseus \"name\") before creating the first NodeHandle"); }
class RoseusStaticData
{
public:
RoseusStaticData() {}
~RoseusStaticData() {
}
boost::shared_ptr<ros::NodeHandle> node;
boost::shared_ptr<ros::Rate> rate;
map<string, boost::shared_ptr<Publisher> > mapAdvertised; ///< advertised topics
map<string, boost::shared_ptr<Subscriber> > mapSubscribed; ///< subscribed topics
map<string, boost::shared_ptr<ServiceServer> > mapServiced; ///< subscribed topics
map<string, Timer > mapTimered; ///< subscribed timers
map<string, boost::shared_ptr<NodeHandle> > mapHandle; ///< for grouping nodehandle
};
static RoseusStaticData s_staticdata;
static bool s_bInstalled = false;
#define s_node s_staticdata.node
#define s_rate s_staticdata.rate
#define s_mapAdvertised s_staticdata.mapAdvertised
#define s_mapSubscribed s_staticdata.mapSubscribed
#define s_mapServiced s_staticdata.mapServiced
#define s_mapTimered s_staticdata.mapTimered
#define s_mapHandle s_staticdata.mapHandle
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;
extern pointer LAMCLOSURE;
/***********************************************************
* Message wrapper
************************************************************/
string getString(pointer message, pointer method) {
context *ctx = current_ctx;
pointer r, curclass;
if ((pointer)findmethod(ctx,method,classof(message),&curclass)!=NIL) {
r = csend(ctx,message,method,0);
} else if ((pointer)findmethod(ctx,K_ROSEUS_GET,classof(message),&curclass) != NIL ) {
r = csend(ctx,message,K_ROSEUS_GET,1,method);
} else {
r = NULL;
#ifdef x86_64
ROS_ERROR("could not find method %s for pointer %lx",
get_string(method), (long unsigned int)message);
#else
ROS_ERROR("could not find method %s for pointer %x",
get_string(method), (unsigned int)message);
#endif
}
if ( !isstring(r) ) {
pointer dest=(pointer)mkstream(ctx,K_OUT,makebuffer(64));
prinx(ctx,message,dest);
pointer str = makestring((char *)dest->c.stream.buffer->c.str.chars,
intval(dest->c.stream.count));
ROS_ERROR("send %s to %s returns nil", get_string(method), get_string(str));
}
ROS_ASSERT(isstring(r));
string ret = (char *)get_string(r);
return ret;
}
int getInteger(pointer message, pointer method) {
context *ctx = current_ctx;
pointer a,curclass;
vpush(message);
a = (pointer)findmethod(ctx,method,classof(message),&curclass);
if (a!=NIL) {
pointer r = csend(ctx,message,method,0);
vpop(); // message
return (ckintval(r));
} else {
#ifdef x86_64
ROS_ERROR("could not find method %s for pointer %lx",
get_string(method), (long unsigned int)message);
#else
ROS_ERROR("could not find method %s for pointer %x",
get_string(method), (unsigned int)message);
#endif
vpop(); // message
}
return 0;
}
class EuslispMessage
{
public:
pointer _message;
boost::shared_ptr<map<string, string> > _connection_header;
EuslispMessage(pointer message) : _message(message) {
}
EuslispMessage(const EuslispMessage &r) {
context *ctx = current_ctx;
if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
if ( isclass(r._message) ) {
//ROS_ASSERT(isclass(r._message));
vpush(r._message);
_message = makeobject(r._message);
vpush(_message);
csend(ctx,_message,K_ROSEUS_INIT,0);
vpop(); // _message
vpop(); // r._message
} else {
ROS_WARN("r._message must be class");prinx(ctx,r._message,ERROUT);flushstream(ERROUT);terpri(ERROUT);
_message = r._message;
}
}
virtual ~EuslispMessage() { }
virtual void replaceContents (pointer newMessage) {
_message = newMessage;
}
virtual const string __getDataType() const {
return getString(_message, K_ROSEUS_DATATYPE);
}
virtual const string __getMD5Sum() const {
return getString(_message, K_ROSEUS_MD5SUM);
}
virtual const string __getMessageDefinition() const {
return getString(_message, K_ROSEUS_DEFINITION);
}
virtual const string __getServiceDataType() const {
return getString(_message, K_ROSEUS_DATATYPE);
}
virtual const string __getServerMD5Sum() const {
return getString(_message, K_ROSEUS_MD5SUM);
}
uint32_t serializationLength() const {
context *ctx = current_ctx;
if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
pointer a,curclass;
a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(_message),&curclass);
ROS_ASSERT(a!=NIL);
return getInteger(_message, K_ROSEUS_SERIALIZATION_LENGTH);
}
virtual uint8_t *serialize(uint8_t *writePtr, uint32_t seqid) const
{
context *ctx = current_ctx;
if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
pointer a,curclass;
vpush(_message); // to avoid GC
uint32_t len = serializationLength();
vpop(); // pop _message
a = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZE,classof(_message),&curclass);
ROS_ASSERT(a!=NIL);
pointer r = csend(ctx,_message,K_ROSEUS_SERIALIZE,0);
ROS_ASSERT(isstring(r));
memcpy(writePtr, get_string(r), len);
//ROS_INFO("serialize");
return writePtr + len;
}
virtual uint8_t *deserialize(uint8_t *readPtr, uint32_t sz)
{
context *ctx = current_ctx;
if (ctx!=euscontexts[0])ROS_WARN("ctx is not correct %d\n",thr_self());
pointer a,curclass;
if ( sz == 0 ) {
ROS_DEBUG("empty message!");
return readPtr;
}
vpush(_message);
a = (pointer)findmethod(ctx,K_ROSEUS_DESERIALIZE,classof(_message),&curclass);
ROS_ASSERT(a!=NIL);
pointer p = makestring((char *)readPtr, sz);
pointer r;
r = csend(ctx,_message,K_ROSEUS_DESERIALIZE,1,p);
ROS_ASSERT(r!=NIL);
//ROS_INFO("deserialize %d", __serialized_length);
vpop(); // pop _message
return readPtr + sz;
}
};
void StoreConnectionHeader(EuslispMessage *eus_msg) {
if ( eus_msg->_connection_header == NULL ||
eus_msg->_connection_header->size() == 0 ) {
return;
}
context *ctx = current_ctx;
// store conection headers
register pointer ret, header;
ret = cons(ctx, NIL, NIL);
header = ret;
vpush(ret);
for(map<string, string>::iterator it = eus_msg->_connection_header->begin(); it != eus_msg->_connection_header->end(); it++){
ccdr(ret) = cons(ctx,cons(ctx,makestring((char *)it->first.c_str(), it->first.length()),
makestring((char *)it->second.c_str(), it->second.length())),NIL);
ret = ccdr(ret);
}
/* (setslot obj class index newval) */
pointer slot_args[4] = {eus_msg->_message, classof(eus_msg->_message), K_ROSEUS_CONNECTION_HEADER, ccdr(header)};
SETSLOT(ctx, 4, slot_args);
vpop();
}
namespace ros{
namespace serialization{
template<> struct Serializer<EuslispMessage> {
template<typename Stream>
inline static void write(Stream& stream, boost::call_traits<EuslispMessage>::param_type t) {
t.serialize(stream.getData(), 0);
}
template<typename Stream>
inline static void read(Stream& stream, boost::call_traits<EuslispMessage>::reference t) {
t.deserialize(stream.getData(), stream.getLength());
}
inline static uint32_t serializedLength(boost::call_traits<EuslispMessage>::param_type t) {
return t.serializationLength();
}
};
}
}
/************************************************************
* Subscriptions
************************************************************/
class EuslispSubscriptionCallbackHelper : public ros::SubscriptionCallbackHelper {
public:
pointer _scb,_args;
EuslispMessage _msg;
EuslispSubscriptionCallbackHelper(pointer scb, pointer args,pointer tmpl) : _args(args), _msg(tmpl) {
context *ctx = current_ctx;
//ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
//ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
if (piscode(scb)) { // compiled code
_scb=scb;
} else if ((ccar(scb))==LAMCLOSURE) { // uncompiled code
if ( ccar(ccdr(scb)) != NIL ) { // function
_scb=ccar(ccdr(scb));
} else { // lambda function
_scb=scb;
}
} else {
ROS_ERROR("subscription callback function install error");
}
// avoid gc
pointer p=gensym(ctx);
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));
}
~EuslispSubscriptionCallbackHelper() {
ROS_ERROR("subscription gc");
}
virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams& param) {
#if DEBUG
cerr << __PRETTY_FUNCTION__ << endl;
cerr << "param.length = " << param.length << endl;
cerr << "param.buffer = " << (param.buffer + 4) << endl;
cerr << "c_header == " << param.connection_header << endl;
for(map<string, string>::iterator it = param.connection_header->begin(); it != param.connection_header->end(); it++){
cerr << " " << it->first << " : " << it->second << endl;
}
#endif
ros::VoidConstPtr ptr(new EuslispMessage(_msg));
EuslispMessage *eus_msg = (EuslispMessage *)(ptr.get());
eus_msg->deserialize(param.buffer, param.length);
eus_msg->_connection_header = param.connection_header;
return ptr;
}
virtual void call(ros::SubscriptionCallbackHelperCallParams& param) {
EuslispMessage* eus_msg = (EuslispMessage *)((void *)param.event.getConstMessage().get());
context *ctx = current_ctx;
pointer argp=_args;
int argc=0;
//ROS_WARN("func");prinx(ctx,_scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
//ROS_WARN("argc");prinx(ctx,argp,ERROUT);flushstream(ERROUT);terpri(ERROUT);
vpush(eus_msg->_message); // to avoid GC
if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
}
// store connection header
StoreConnectionHeader(eus_msg);
while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
vpush((pointer)(eus_msg->_message));argc++;
ufuncall(ctx,(ctx->callfp?ctx->callfp->form:NIL),_scb,(pointer)(ctx->vsp-argc),NULL,argc);
while(argc-->0)vpop();
vpop(); // remove eus_msg._message
}
virtual const std::type_info& getTypeInfo() {
return typeid(EuslispMessage);
}
virtual bool isConst(){
return true;
}
virtual bool hasHeader(){
return true;
}
};
/************************************************************
* ServiceCall
************************************************************/
class EuslispServiceCallbackHelper : public ros::ServiceCallbackHelper {
public:
pointer _scb, _args;
EuslispMessage _req, _res;
string md5, datatype, requestDataType, responseDataType,
requestMessageDefinition, responseMessageDefinition;
EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass) : _args(args), _req(reqclass), _res(resclass), md5(smd5), datatype(sdatatype) {
context *ctx = current_ctx;
//ROS_WARN("func");prinx(ctx,scb,ERROUT);flushstream(ERROUT);terpri(ERROUT);
//ROS_WARN("argc");prinx(ctx,args,ERROUT);flushstream(ERROUT);terpri(ERROUT);
if (piscode(scb)) { // compiled code
_scb=scb;
} else if ((ccar(scb))==LAMCLOSURE) {
if ( ccar(ccdr(scb)) != NIL ) { // function
_scb=ccar(ccdr(scb));
} else { // lambda function
_scb=scb;
}
} else {
ROS_ERROR("service callback function install error");
}
// avoid gc
pointer p=gensym(ctx);
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));
requestDataType = _req.__getDataType();
responseDataType = _res.__getDataType();
requestMessageDefinition = _req.__getMessageDefinition();
responseMessageDefinition = _res.__getMessageDefinition();
}
~EuslispServiceCallbackHelper() { }
virtual boost::shared_ptr<EuslispMessage> createRequest() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_req)); }
virtual boost::shared_ptr<EuslispMessage> createResponse() { return boost::shared_ptr<EuslispMessage>(new EuslispMessage(_res)); }
virtual std::string getMD5Sum() { return md5; }
virtual std::string getDataType() { return datatype; }
virtual std::string getRequestDataType() { return requestDataType; }
virtual std::string getResponseDataType() { return responseDataType; }
virtual std::string getRequestMessageDefinition() { return requestMessageDefinition; }
virtual std::string getResponseMessageDefinition() { return responseMessageDefinition; }
virtual bool call(ros::ServiceCallbackHelperCallParams& params) {
#if DEBUG
cerr << __PRETTY_FUNCTION__ << endl;
cerr << "param.length = " << params.request.num_bytes << endl;
cerr << "param.buffer = " << (params.request.message_start + 4) << endl;
cerr << "c_header == " << params.connection_header << endl;
for(map<string, string>::iterator it = params.connection_header->begin(); it != params.connection_header->end(); it++){
cerr << " " << it->first << " : " << it->second << endl;
}
#endif
context *ctx = current_ctx;
pointer r, argp=_args;
int argc=0;
vpush(_res._message); // _res._message
vpush(_req._message); // _res._message, _req._message
if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
ROS_ERROR("%s : can't find callback function", __PRETTY_FUNCTION__);
}
// Deserialization
EuslispMessage eus_msg(_req);
vpush(eus_msg._message); // _res._message, _req._message, eus_msg._message
eus_msg.deserialize(params.request.message_start, params.request.num_bytes);
// store connection header
eus_msg._connection_header = params.connection_header;
StoreConnectionHeader(&eus_msg);
while(argp!=NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
vpush((pointer) eus_msg._message);argc++;
r = ufuncall(ctx, (ctx->callfp?ctx->callfp->form:NIL),
_scb, (pointer)(ctx->vsp-argc),
NULL, argc);
while(argc-->0)vpop();// _res._message, _req._message, eus_msg._message
vpush(r); // _res._message, _req._message, eus_msg._message, r,
// Serializaion
EuslispMessage eus_res(_res);
eus_res.replaceContents(r);
// check return value is valid
pointer ret_serialize_method, ret_class;
if (ispointer(r)) {
ret_serialize_method = (pointer)findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(r),&ret_class); }
if (!ispointer(r) || ret_serialize_method == NIL) {
ROS_ERROR("you may not return valid value in service callback");
vpop(); // _res._message, _req._message, eus_msg._message, r
vpop(); // _res._message, _req._message, eus_msg._message
vpop(); // _res._message, _req._message,
vpop(); // _res._message
return false;
}
vpush(eus_res._message); // _res._message, _req._message, eus_msg._message, r, eus_res._message
uint32_t serialized_length = eus_res.serializationLength();
params.response.num_bytes = serialized_length + 5; // add 5 bytes of message header
params.response.buf.reset (new uint8_t[params.response.num_bytes]);
params.response.message_start = 0;
// SerializedResponseMessage
uint8_t *tmp = params.response.buf.get();
*tmp++ = 1; // 1 byte of success services flag, now always set true
*tmp++ = (uint8_t)((serialized_length >> 0) & 0xFF); // 4bytes of message length
*tmp++ = (uint8_t)((serialized_length >> 8) & 0xFF);
*tmp++ = (uint8_t)((serialized_length >> 16) & 0xFF);
*tmp++ = (uint8_t)((serialized_length >> 24) & 0xFF);
eus_res.serialize(tmp, 0);
// store connection header
eus_res._connection_header = params.connection_header;
StoreConnectionHeader(&eus_res);
#if DEBUG
cerr << "num bytes = " << params.response.num_bytes << endl;
ROS_INFO("message_start = %X",params.response.message_start);
ROS_INFO("message_ptr = %X",params.response.buf.get());
tmp = params.response.buf.get();
for(int i=0;i<params.response.num_bytes;i++){
ROS_INFO("%X", tmp[i]);
}
#endif
vpop(); // _res._message, _req._message, eus_msg._message, r, eus_res._message
vpop(); // _res._message, _req._message, eus_msg._message, r
vpop(); // _res._message, _req._message, eus_msg._message
vpop(); // _res._message, _req._message,
vpop(); // _res._message
return true;
}
};
void roseusSignalHandler(int sig)
{
// memoize for euslisp handler...
context *ctx=euscontexts[thr_self()];
ctx->intsig = sig;
}
/************************************************************
* EUSLISP functions
************************************************************/
pointer ROSEUS(register context *ctx,int n,pointer *argv)
{
char name[256] = "";
uint32_t options = 0;
int cargc = 0;
char *cargv[32];
if( s_bInstalled ) {
ROS_WARN("ROSEUS is already installed as %s", ros::this_node::getName().c_str());
return (T);
}
ckarg(3);
if (isstring(argv[0]))
strncpy(name,(char *)(argv[0]->c.str.chars),255);
else error(E_NOSTRING);
options = ckintval(argv[1]);
pointer p = argv[2];
if (islist(p)) {
while (1) {
if (!iscons(p)) break;
cargv[cargc]=(char *)((ccar(p))->c.str.chars);
cargc++;
p=ccdr(p);
}
} else error(E_NOSEQ);
// convert invalid node name charactors to _, we assume it is '-'
for (unsigned int i=0; i < strlen(name); i++)
if ( ! (isalpha(name[i]) || isdigit(name[i])) ) name[i] = '_';
K_ROSEUS_MD5SUM = defkeyword(ctx,"MD5SUM-");
K_ROSEUS_DATATYPE = defkeyword(ctx,"DATATYPE-");
K_ROSEUS_DEFINITION = defkeyword(ctx,"DEFINITION-");
K_ROSEUS_CONNECTION_HEADER = intern(ctx,"_CONNECTION-HEADER",18,findpkg(makestring("ROS",3)));
K_ROSEUS_SERIALIZATION_LENGTH = defkeyword(ctx,"SERIALIZATION-LENGTH");
K_ROSEUS_SERIALIZE = defkeyword(ctx,"SERIALIZE");
K_ROSEUS_DESERIALIZE = defkeyword(ctx,"DESERIALIZE");
K_ROSEUS_GET = defkeyword(ctx,"GET");
K_ROSEUS_INIT = defkeyword(ctx,"INIT");
K_ROSEUS_REQUEST = defkeyword(ctx,"REQUEST");
K_ROSEUS_RESPONSE = defkeyword(ctx,"RESPONSE");
K_ROSEUS_GROUPNAME = defkeyword(ctx,"GROUPNAME");
K_ROSEUS_ONESHOT = defkeyword(ctx,"ONESHOT");
K_ROSEUS_LAST_EXPECTED = defkeyword(ctx,"LAST-EXPECTED");
K_ROSEUS_LAST_REAL = defkeyword(ctx,"LAST-REAL");
K_ROSEUS_CURRENT_EXPECTED = defkeyword(ctx,"CURRENT-EXPECTED");
K_ROSEUS_CURRENT_REAL = defkeyword(ctx,"CURRENT-REAL");
K_ROSEUS_LAST_DURATION = defkeyword(ctx,"LAST-DURATION");
K_ROSEUS_SEC = defkeyword(ctx,"SEC");
K_ROSEUS_NSEC = defkeyword(ctx,"NSEC");
s_mapAdvertised.clear();
s_mapSubscribed.clear();
s_mapServiced.clear();
s_mapTimered.clear();
s_mapHandle.clear();
/*
set locale to none to let C RTL assume logging string can contain non-ascii characters.
Refer: https://logging.apache.org/log4cxx/latest_stable/faq.html
*/
setlocale(LC_ALL, "");
/*
force to flag ros::init_options::NoSigintHandler.
In fact, this code make no sence, because we steals
SIGINT handler by the following `signal'.
*/
options |= ros::init_options::NoSigintHandler;
/*
clear ros::master::g_uri which is defined in ros::master::init in __roseus.
this occurs if user set unix::setenv("ROS_MASTER_URI") between __roseus and
ROSEUS.
*/
if (!ros::master::g_uri.empty()) {
if ( ros::master::g_uri != getenv("ROS_MASTER_URI") ) {
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"));
ros::master::g_uri.clear();
}
}
try {
ros::init(cargc, cargv, name, options);
} catch (const ros::InvalidNameException &e) {
ROS_ERROR("%s",e.what());
error(E_MISMATCHARG);
return(NIL);
}
s_node.reset(new ros::NodeHandle());
s_rate.reset(new ros::Rate(50));
s_bInstalled = true;
// install signal handler for sigint. DO NOT call unix:signal after
// ros::roseus
signal(SIGINT, roseusSignalHandler);
return (T);
}
pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
string groupname;
string ns;
ckarg2(1, 2);
// ;; arguments ;;
// groupname [ namespace ]
if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
else error(E_NOSTRING);
if ( n > 1 ) {
if(isstring(argv[1])) ns.assign((char *)get_string(argv[1]));
else error(E_NOSTRING);
}
if( s_mapHandle.find(groupname) != s_mapHandle.end() ) {
ROS_DEBUG("groupname %s is already used", groupname.c_str());
return (NIL);
}
boost::shared_ptr<NodeHandle> hd;
if ( n > 1 ) {
hd = boost::shared_ptr<NodeHandle> (new NodeHandle(ns));
s_mapHandle[groupname] = hd;
} else {
hd = boost::shared_ptr<NodeHandle>(new NodeHandle());
s_mapHandle[groupname] = hd;
}
//add callbackqueue to hd
hd->setCallbackQueue( new CallbackQueue() );
return (T);
}
pointer ROSEUS_SPIN(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
while (ctx->intsig==0 && ros::ok()) {
ros::spinOnce();
s_rate->sleep();
}
return (NIL);
}
pointer ROSEUS_SPINONCE(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
ckarg2(0, 1);
// ;; arguments ;;
// [ groupname ]
if ( n > 0 ) {
string groupname;
if (isstring(argv[0])) groupname.assign((char *)get_string(argv[0]));
else error(E_NOSTRING);
map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
if( it == s_mapHandle.end() ) {
ROS_ERROR("Groupname %s is missing", groupname.c_str());
return (T);
}
boost::shared_ptr<NodeHandle > hdl = (it->second);
// spin this nodehandle
((CallbackQueue *)hdl->getCallbackQueue())->callAvailable();
return (NIL);
} else {
ros::spinOnce();
return (NIL);
}
}
pointer ROSEUS_TIME_NOW(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
pointer timevec;
ros::Time t = ros::Time::now();
timevec=makevector(C_INTVECTOR,2);
vpush(timevec);
timevec->c.ivec.iv[0]=t.sec;
timevec->c.ivec.iv[1]=t.nsec;
vpop();
return (timevec);
}
pointer ROSEUS_RATE(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
numunion nu;
ckarg(1);
float timeout=ckfltval(argv[0]);
s_rate.reset(new ros::Rate(timeout));
return(T);
}
pointer ROSEUS_SLEEP(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
s_rate->sleep();
return (T);
}
pointer ROSEUS_DURATION_SLEEP(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
numunion nu;
ckarg(1);
float sleep=ckfltval(argv[0]);
ros::Duration(sleep).sleep();
return(T);
}
pointer ROSEUS_OK(register context *ctx,int n,pointer *argv)
{
if (ros::ok()) {
return (T);
} else {
return (NIL);
}
}
#define def_rosconsole_formatter(funcname, rosfuncname) \
pointer funcname(register context *ctx,int n,pointer *argv) \
{ pointer *argv2,msg; \
int argc2; \
argc2 = n+1; \
argv2 = (pointer *)malloc(sizeof(pointer)*argc2); \
argv2[0] = NIL; \
for(int i=0;i<n;i++) argv2[i+1]=argv[i] ; \
msg = XFORMAT(ctx, argc2, argv2); \
rosfuncname("%s", msg->c.str.chars); \
free(argv2); \
return (T); \
}
def_rosconsole_formatter(ROSEUS_ROSDEBUG, ROS_DEBUG)
def_rosconsole_formatter(ROSEUS_ROSINFO, ROS_INFO)
def_rosconsole_formatter(ROSEUS_ROSWARN, ROS_WARN)
def_rosconsole_formatter(ROSEUS_ROSERROR, ROS_ERROR)
def_rosconsole_formatter(ROSEUS_ROSFATAL, ROS_FATAL)
pointer ROSEUS_EXIT(register context *ctx,int n,pointer *argv)
{
ROS_INFO("%s", __PRETTY_FUNCTION__);
if( s_bInstalled ) {
ROS_INFO("exiting roseus %ld", (n==0)?n:ckintval(argv[0]));
s_mapAdvertised.clear();
s_mapSubscribed.clear();
s_mapServiced.clear();
s_mapTimered.clear();
s_mapHandle.clear();
ros::shutdown();
}
if (n==0) _exit(0);
else _exit(ckintval(argv[0]));
}
/************************************************************
* ROSEUS Publisher/Subscriber
************************************************************/
pointer ROSEUS_SUBSCRIBE(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
string topicname;
pointer message, fncallback, args;
int queuesize = 1;
NodeHandle *lnode = s_node.get();
// ;; arguments ;;
// topicname message_type callbackfunc args0 ... argsN [ queuesize ] [ :groupname groupname ]
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
if (n > 1 && issymbol(argv[n-2]) && isstring(argv[n-1])) {
if (argv[n-2] == K_ROSEUS_GROUPNAME) {
string groupname;
groupname.assign((char *)get_string(argv[n-1]));
map<string, boost::shared_ptr<NodeHandle > >::iterator it = s_mapHandle.find(groupname);
if( it != s_mapHandle.end() ) {
ROS_DEBUG("subscribe with groupname=%s", groupname.c_str());
lnode = (it->second).get();
} else {
ROS_ERROR("Groupname %s is missing. Topic %s is not subscribed. Call (ros::create-nodehandle \"%s\") first.",
groupname.c_str(), topicname.c_str(), groupname.c_str());
return (NIL);
}
n -= 2;
}
}
if (isint(argv[n-1])) {queuesize = ckintval(argv[n-1]);n--;}
ROS_DEBUG("subscribe %s queuesize=%d", topicname.c_str(), queuesize);
// TODO:need error checking
message = argv[1];
fncallback = argv[2];
args=NIL;
for (int i=n-1;i>=3;i--) args=cons(ctx,argv[i],args);
EuslispMessage msg(message);
boost::shared_ptr<SubscriptionCallbackHelper> *callback =
(new boost::shared_ptr<SubscriptionCallbackHelper>
(new EuslispSubscriptionCallbackHelper(fncallback, args, message)));
SubscribeOptions so(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType());
so.helper = *callback;
Subscriber subscriber = lnode->subscribe(so);
boost::shared_ptr<Subscriber> sub = boost::shared_ptr<Subscriber>(new Subscriber(subscriber));
if ( !!sub ) {
s_mapSubscribed[topicname] = sub;
} else {
ROS_ERROR("s_mapSubscribed");
}
return (T);
}
pointer ROSEUS_UNSUBSCRIBE(register context *ctx,int n,pointer *argv)
{
string topicname;
ckarg(1);
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
bool bSuccess = s_mapSubscribed.erase(topicname)>0;
return (bSuccess?T:NIL);
}
pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx,int n,pointer *argv)
{
string topicname;
int ret;
ckarg(1);
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
bool bSuccess = false;
map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
if( it != s_mapSubscribed.end() ) {
boost::shared_ptr<Subscriber> subscriber = (it->second);
ret = subscriber->getNumPublishers();
bSuccess = true;
}
return (bSuccess?(makeint(ret)):NIL);
}
pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx,int n,pointer *argv)
{
string topicname;
string ret;
ckarg(1);
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
bool bSuccess = false;
map<string, boost::shared_ptr<Subscriber> >::iterator it = s_mapSubscribed.find(topicname);
if( it != s_mapSubscribed.end() ) {
boost::shared_ptr<Subscriber> subscriber = (it->second);
ret = subscriber->getTopic();
bSuccess = true;
}
return (bSuccess?(makestring((char *)ret.c_str(), ret.length())):NIL);
}
pointer ROSEUS_ADVERTISE(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
string topicname;
pointer message;
int queuesize = 1;
bool latch = false;
ckarg2(2,4);
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
message = argv[1];
if ( n > 2 ) {
queuesize = ckintval(argv[2]);
}
if ( n > 3 ) {
latch = (argv[3]!=NIL ? true : false);
}
ROS_DEBUG("advertise %s %d %d", topicname.c_str(), queuesize, latch);
if( s_mapAdvertised.find(topicname) != s_mapAdvertised.end() ) {
ROS_WARN("topic %s already advertised", topicname.c_str());
return (NIL);
}
EuslispMessage msg(message);
AdvertiseOptions ao(topicname, queuesize, msg.__getMD5Sum(), msg.__getDataType(), msg.__getMessageDefinition());
ao.latch = latch;
Publisher publisher = s_node->advertise(ao);
boost::shared_ptr<Publisher> pub = boost::shared_ptr<Publisher>(new Publisher(publisher));
if ( !!pub ) {
s_mapAdvertised[topicname] = pub;
} else {
ROS_ERROR("s_mapAdvertised");
}
return (T);
}
pointer ROSEUS_UNADVERTISE(register context *ctx,int n,pointer *argv)
{
string topicname;
ckarg(1);
if (isstring(argv[0])) topicname = ros::names::resolve((char *)get_string(argv[0]));
else error(E_NOSTRING);
bool bSuccess = s_mapAdvertised.erase(topicname)>0;
return (bSuccess?T:NIL);
}
pointer ROSEUS_PUBLISH(register context *ctx,int n,pointer *argv)
{
isInstalledCheck;
string topicname;
pointer emessage;