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> 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 94 char modname[] =
"___roseus";
123 #define isInstalledCheck \ 124 if( ! ros::ok() ) { error(E_USER,"You must call (ros::roseus \"name\") before creating the first NodeHandle"); } 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 152 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;
163 r =
csend(ctx,message,method,0);
165 r =
csend(ctx,message,K_ROSEUS_GET,1,method);
169 ROS_ERROR(
"could not find method %s for pointer %lx",
170 get_string(method), (
long unsigned int)message);
172 ROS_ERROR(
"could not find method %s for pointer %x",
176 if ( !isstring(r) ) {
178 prinx(ctx,message,dest);
196 return (ckintval(r));
199 ROS_ERROR(
"could not find method %s for pointer %lx",
200 get_string(method), (
long unsigned int)message);
202 ROS_ERROR(
"could not find method %s for pointer %x",
226 csend(ctx,_message,K_ROSEUS_INIT,0);
237 _message = newMessage;
241 return getString(_message, K_ROSEUS_DATATYPE);
244 return getString(_message, K_ROSEUS_MD5SUM);
247 return getString(_message, K_ROSEUS_DEFINITION);
250 return getString(_message, K_ROSEUS_DATATYPE);
253 return getString(_message, K_ROSEUS_MD5SUM);
260 a = (
pointer)
findmethod(ctx,K_ROSEUS_SERIALIZATION_LENGTH,classof(_message),&curclass);
262 return getInteger(_message, K_ROSEUS_SERIALIZATION_LENGTH);
265 virtual uint8_t *
serialize(uint8_t *writePtr, uint32_t seqid)
const 271 uint32_t len = serializationLength();
280 return writePtr + len;
298 r =
csend(ctx,_message,K_ROSEUS_DESERIALIZE,1,p);
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);
330 namespace serialization{
332 template<
typename Stream>
334 t.serialize(stream.
getData(), 0);
337 template<
typename Stream>
341 inline static uint32_t
serializedLength(boost::call_traits<EuslispMessage>::param_type t) {
342 return t.serializationLength();
362 }
else if ((ccar(scb))==LAMCLOSURE) {
363 if ( ccar(ccdr(scb)) !=
NIL ) {
364 _scb=ccar(ccdr(scb));
369 ROS_ERROR(
"subscription callback function install error");
380 cerr << __PRETTY_FUNCTION__ << endl;
381 cerr <<
"param.length = " << param.
length << endl;
382 cerr <<
"param.buffer = " << (param.
buffer + 4) << endl;
385 cerr <<
" " << it->first <<
" : " << it->second << endl;
403 if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
404 ROS_ERROR(
"%s : can't find callback function", __PRETTY_FUNCTION__);
410 while(argp!=
NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
414 while(argc-->0)vpop();
435 string md5, datatype, requestDataType, responseDataType,
445 }
else if ((ccar(scb))==LAMCLOSURE) {
446 if ( ccar(ccdr(scb)) !=
NIL ) {
447 _scb=ccar(ccdr(scb));
452 ROS_ERROR(
"service callback function install error");
477 cerr << __PRETTY_FUNCTION__ << endl;
482 cerr <<
" " << it->first <<
" : " << it->second << endl;
492 if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
493 ROS_ERROR(
"%s : can't find callback function", __PRETTY_FUNCTION__);
504 while(argp!=
NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
510 while(argc-->0)vpop();
516 pointer ret_serialize_method, ret_class;
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");
536 *tmp++ = (uint8_t)((serialized_length >> 0) & 0xFF);
537 *tmp++ = (uint8_t)((serialized_length >> 8) & 0xFF);
538 *tmp++ = (uint8_t)((serialized_length >> 16) & 0xFF);
539 *tmp++ = (uint8_t)((serialized_length >> 24) & 0xFF);
585 if (isstring(argv[0]))
586 strncpy(name,(
char *)(argv[0]->c.str.chars),255);
588 options = ckintval(argv[1]);
592 if (!iscons(p))
break;
593 cargv[cargc]=(
char *)((ccar(p))->c.str.chars);
600 for (
unsigned int i=0; i < strlen(name); i++)
601 if ( ! (isalpha(name[i]) || isdigit(name[i])) ) name[i] =
'_';
604 K_ROSEUS_DATATYPE =
defkeyword(ctx,
"DATATYPE-");
605 K_ROSEUS_DEFINITION =
defkeyword(ctx,
"DEFINITION-");
607 K_ROSEUS_SERIALIZATION_LENGTH =
defkeyword(ctx,
"SERIALIZATION-LENGTH");
608 K_ROSEUS_SERIALIZE =
defkeyword(ctx,
"SERIALIZE");
609 K_ROSEUS_DESERIALIZE =
defkeyword(ctx,
"DESERIALIZE");
613 K_ROSEUS_RESPONSE =
defkeyword(ctx,
"RESPONSE");
614 K_ROSEUS_GROUPNAME =
defkeyword(ctx,
"GROUPNAME");
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");
634 setlocale(LC_ALL,
"");
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"));
683 if (isstring(argv[0])) groupname.assign((
char *)
get_string(argv[0]));
686 if(isstring(argv[1])) ns.assign((
char *)
get_string(argv[1]));
691 ROS_DEBUG(
"groupname %s is already used", groupname.c_str());
728 if (isstring(argv[0])) groupname.assign((
char *)
get_string(argv[0]));
731 map<string, boost::shared_ptr<NodeHandle > >::iterator it =
s_mapHandle.find(groupname);
733 ROS_ERROR(
"Groupname %s is missing", groupname.c_str());
798 #define def_rosconsole_formatter(funcname, rosfuncname) \ 799 pointer funcname(register context *ctx,int n,pointer *argv) \ 800 { pointer *argv2,msg; \ 803 argv2 = (pointer *)malloc(sizeof(pointer)*argc2); \ 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); \ 820 ROS_INFO(
"%s", __PRETTY_FUNCTION__);
822 ROS_INFO(
"exiting roseus %ld", (n==0)?n:ckintval(argv[0]));
831 else _exit(ckintval(argv[0]));
850 if (n > 1 && issymbol(argv[n-2]) && isstring(argv[n-1])) {
851 if (argv[n-2] == K_ROSEUS_GROUPNAME) {
853 groupname.assign((
char *)
get_string(argv[n-1]));
854 map<string, boost::shared_ptr<NodeHandle > >::iterator it =
s_mapHandle.find(groupname);
856 ROS_DEBUG(
"subscribe with groupname=%s", groupname.c_str());
857 lnode = (it->second).
get();
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());
866 if (isint(argv[n-1])) {queuesize = ckintval(argv[n-1]);n--;}
867 ROS_DEBUG(
"subscribe %s queuesize=%d", topicname.c_str(), queuesize);
870 fncallback = argv[2];
872 for (
int i=n-1;i>=3;i--) args=
cons(ctx,argv[i],args);
901 return (bSuccess?
T:
NIL);
913 bool bSuccess =
false;
914 map<string, boost::shared_ptr<Subscriber> >::iterator it =
s_mapSubscribed.find(topicname);
917 ret = subscriber->getNumPublishers();
933 bool bSuccess =
false;
934 map<string, boost::shared_ptr<Subscriber> >::iterator it =
s_mapSubscribed.find(topicname);
937 ret = subscriber->getTopic();
958 queuesize = ckintval(argv[2]);
961 latch = (argv[3]!=
NIL ?
true :
false);
963 ROS_DEBUG(
"advertise %s %d %d", topicname.c_str(), queuesize, latch);
965 ROS_WARN(
"topic %s already advertised", topicname.c_str());
993 return (bSuccess?
T:
NIL);
1008 bool bSuccess =
false;
1009 map<string, boost::shared_ptr<Publisher> >::iterator it =
s_mapAdvertised.find(topicname);
1013 publisher->publish(message);
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());
1035 bool bSuccess =
false;
1036 map<string, boost::shared_ptr<Publisher> >::iterator it =
s_mapAdvertised.find(topicname);
1039 ret = publisher->getNumSubscribers();
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());
1061 bool bSuccess =
false;
1062 map<string, boost::shared_ptr<Publisher> >::iterator it =
s_mapAdvertised.find(topicname);
1065 ret = publisher->getTopic();
1084 int32_t timeout = -1;
1087 timeout = (int32_t)ckintval(argv[1]);
1091 return (bSuccess?
T:
NIL);
1105 return (bSuccess?
T:
NIL);
1113 bool persist =
false;
1119 persist = (argv[2] !=
NIL ?
true :
false);
1121 static std::map<std::string, ros::ServiceServerLinkPtr> service_link_cache;
1122 static std::map<std::string, std::string> service_md5_cache;
1134 if ( service_link_cache.find(service) != service_link_cache.end() &&
1135 ( ! service_link_cache[service]->isValid() ||
1136 service_md5_cache[service] !=request.
__getMD5Sum() )) {
1138 service_link_cache[service].reset();
1139 service_link_cache.erase(service);
1140 service_md5_cache.erase(service);
1143 if (service_link_cache.find(service) == service_link_cache.end()) {
1145 service_md5_cache[service] = request.
__getMD5Sum();
1147 link = service_link_cache[service];
1152 bool bSuccess =
true;
1155 if (link && link->isValid()) {
1156 bSuccess = link->call(ser_req, ser_resp);
1160 }
catch (std::exception& e) {
1161 ROS_ERROR(
"Exception thrown while deserializing service call: %s", e.what());
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;
1182 ROS_ERROR(
"Failed to establish connection to service server");
1187 ROS_ERROR(
"attempted to call service %s, but failed ",
1204 fncallback = argv[2];
1206 for (
int i=n-1;i>=3;i--) args=
cons(ctx,argv[i],args);
1208 ROS_INFO(
"service %s already advertised", service.c_str());
1214 pointer request(
csend(ctx,emessage,K_ROSEUS_GET,1,K_ROSEUS_REQUEST));
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();
1247 ROS_DEBUG(
"unadvertise %s", service.c_str());
1250 return (bSuccess?
T:
NIL);
1257 if ( islist(argp) && islist(ccar(argp))) {
1261 std::ostringstream stringstream;
1262 stringstream <<
"<value><struct>";
1267 if ( issymbol(ccar(v)) ) {
1269 boost::algorithm::to_lower(skey);
1270 stringstream <<
"<member><name>" << skey <<
"</name><value><boolean>0</boolean></value></member>";
1279 stringstream <<
"</struct></value>";
1280 j=0; rpc_value.
fromXml(stringstream.str(), &j);
1286 if ( issymbol(ccar(v)) ) {
1288 boost::algorithm::to_lower(skey);
1291 rpc_value[skey] = p;
1296 }
else if ( islist(argp) ) {
1301 i = 0;
while ( islist(a) ) { a=ccdr(a); i++; }
1306 while ( islist(a) ) {
1313 }
else if ( isstring(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) {
1321 }
else if (argp ==
NIL) {
1323 }
else if ( issymbol(argp) ) {
1325 boost::algorithm::to_lower(s);
1326 rpc_value = s.c_str();
1339 if (isstring(argv[0])) key.assign((
char *)
get_string(argv[0]));
1354 if ( rpc_value )
return T;
else return NIL;
1357 return makeflt((
double)rpc_value);
1360 return makeint((
int)rpc_value);
1370 for (
int i = 0; i < rpc_value.
size(); i++){
1382 while(it !=rpc_value.
end()) {
1387 ccdr(ret) =
cons(ctx, tmp,
NIL);
1409 for (
int i = 0; i < param_list.
size(); i++){
1411 if ( param_list[i] ){
1456 if (isstring(argv[0])) key.assign((
char *)
get_string(argv[0]));
1483 ROS_ERROR(
"unknown ros::param::get, key=%s", key.c_str());
1496 if (isstring(argv[0])) key.assign((
char *)
get_string(argv[0]));
1522 ROS_ERROR(
"unknown ros::param::get, key=%s", key.c_str());
1534 if (isstring(argv[0])) key.assign((
char *)
get_string(argv[0]));
1545 if (isstring(argv[0])) key.assign((
char *)
get_string(argv[0]));
1556 if (isstring(argv[0])) pkg.assign((
char *)
get_string(argv[0]));
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()));
1565 if (
rp.
find(pkg,path)==
true)
return(
makestring((
char *)path.c_str(),path.length()));
1567 }
catch (runtime_error &e) {
1578 if (isstring(argv[0])) pkg.assign((
char *)
get_string(argv[0]));
1583 std::vector<std::string> flags;
1584 std::vector<rospack::Stackage*> stackages;
1588 std::vector<std::string> deps;
1589 if (
rp.
deps(pkg,
false,deps)) {
1594 for (std::vector<std::string>::iterator it = deps.begin() ; it != deps.end(); it++) {
1602 }
catch (runtime_error &e) {
1613 if (isstring(argv[0])) pkg.assign((
char *)
get_string(argv[0]));
1615 if (isstring(argv[1])) attrib.assign((
char *)
get_string(argv[1]));
1618 std::vector<std::string> flags;
1619 if (
rp.
plugins(pkg, attrib,
"", flags)) {
1623 for (
size_t i = 0; i < flags.size(); i++) {
1625 std::vector<std::string> parsed_string;
1626 boost::algorithm::split(parsed_string, flags[i], boost::is_any_of(
" "));
1631 makestring((
char*)value.c_str(), value.length())),
1643 catch (runtime_error &e) {
1653 src.assign((
char *)(argv[0]->c.str.chars));
1655 return(
makestring((
char *)dst.c_str(), dst.length()));
1671 return(
makestring((
char *)ns.c_str(), ns.length()));
1678 if (isstring(argv[0])) logger.assign((
char *)
get_string(argv[0]));
1680 int log_level =
intval(argv[1]);
1702 bool success = ::ros::console::set_logger_level(logger, level);
1716 return makestring((
char*)host.c_str(), host.length());
1732 for (ros::V_string::iterator it = nodes.begin() ; it != nodes.end(); it++) {
1754 return makestring((
char*)uri.c_str(), uri.length());
1770 for (ros::master::V_TopicInfo::iterator it = topics.begin() ; it != topics.end(); it++) {
1774 ccdr(ret) =
cons(ctx, tmp,
NIL);
1800 if(!memcmp(
classtab[i].def->c.cls.name->c.sym.pname->c.str.chars,(
char *)
"TIMER-EVENT",11)) {
1804 if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==LAMCLOSURE ) ) {
1805 ROS_ERROR(
"%s : can't find callback function", __PRETTY_FUNCTION__);
1809 csend(ctx,tevent,K_ROSEUS_INIT,0);
1821 while(argp!=
NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
1822 vpush((
pointer)(tevent));argc++;
1825 while(argc-->0)vpop();
1834 bool oneshot =
false;
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 ) {
1851 if (piscode(argv[1])) {
1853 std::ostringstream stringstream;
1854 stringstream << reinterpret_cast<long>(argv[2]) <<
" ";
1855 for (
int i=3; i<
n;i++)
1857 fncallname = stringstream.str();
1858 }
else if ((ccar(argv[1]))==LAMCLOSURE) {
1859 if ( ccar(ccdr(argv[1])) !=
NIL ) {
1860 fncallback=ccar(ccdr(argv[1]));
1864 std::ostringstream stringstream;
1865 stringstream << reinterpret_cast<long>(argv[1]);
1866 fncallname = stringstream.str();
1869 ROS_ERROR(
"subscription callback function install error");
1874 for (
int i=n-1;i>=2;i--) args=
cons(ctx,argv[i],args);
1881 ROS_DEBUG(
"create timer %s at %f (oneshot=%d)", fncallname.c_str(), period, oneshot);
1894 #ifdef ROSPACK_EXPORT 1896 std::vector<std::string> search_path;
1916 "&optional groupname ;; spin only group\n\n" 1917 "Process a single round of callbacks.\n");
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.");
1924 defun(ctx,
"ROS-DEBUG",argv[0],(
pointer (*)())ROSEUS_ROSDEBUG,
1925 "write mesage to debug output\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");
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" 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" 1948 " (defclass string-cb-class\n" 1949 " :super propertied-object\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" 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)");
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");
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.");
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");
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)");
2012 "Create ros NodeHandle with given group name. \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");
2028 pointer_update(Spevalof(
PACKAGE),p);
2031 l=
makestring(REPOVERSION,strlen(REPOVERSION));
2034 QREPOVERSION=
defvar(ctx,
"ROSEUS-REPO-VERSION", l, rospkg);
2041 size_t pos = arg.find(
":=");
2042 if (pos != std::string::npos) {
2045 remappings[local_name] = external_name;
context * euscontexts[MAXTHREAD]
pointer prinx(context *, pointer, pointer)
map< string, boost::shared_ptr< ServiceServer > > mapServiced
subscribed topics
pointer ROSEUS(register context *ctx, int n, pointer *argv)
ROSCPP_DECL uint32_t getPort()
pointer ROSEUS_WAIT_FOR_SERVICE(register context *ctx, int n, pointer *argv)
int getInteger(pointer message, pointer method)
pointer intern(context *, char *, int, pointer)
ROSCPP_DECL const std::string & getURI()
pointer makeint(eusinteger_t v)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
pointer K_ROSEUS_RESPONSE
EuslispServiceCallbackHelper(pointer scb, pointer args, string smd5, string sdatatype, pointer reqclass, pointer resclass)
pointer ROSEUS_UNADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
static RoseusStaticData s_staticdata
static void read(Stream &stream, boost::call_traits< EuslispMessage >::reference t)
WallDuration last_duration
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
virtual const string __getDataType() const
ValueStruct::iterator iterator
pointer ROSEUS_SERVICE_CALL(register context *ctx, int n, pointer *argv)
virtual std::string getDataType()
bool depsOnDetail(const std::string &name, bool direct, std::vector< Stackage * > &deps, bool ignore_missing=false)
void operator()(const ros::TimerEvent &event)
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())
static uint32_t serializedLength(boost::call_traits< EuslispMessage >::param_type t)
pointer findmethod(context *, pointer, pointer, pointer *)
pointer ROSEUS_TIME_NOW(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GET_NODES(register context *ctx, int n, pointer *argv)
virtual void replaceContents(pointer newMessage)
void init(const M_string &remappings)
pointer ROSEUS_SPIN(register context *ctx, int n, pointer *argv)
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)
pointer defkeyword(context *, char *)
pointer K_ROSEUS_SERIALIZE
virtual std::string getResponseMessageDefinition()
pointer SETSLOT(context *, int, pointer *)
virtual const string __getMessageDefinition() const
SerializedMessage response
pointer K_ROSEUS_CONNECTION_HEADER
ROSCPP_DECL const std::string & getName()
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
void EusValueToXmlRpc(register context *ctx, pointer argp, XmlRpc::XmlRpcValue &rpc_value)
void deserializeMessage(const SerializedMessage &m, M &message)
struct ros::TimerEvent::@0 profile
pointer K_ROSEUS_DESERIALIZE
pointer ROSEUS_UNADVERTISE(register context *ctx, int n, pointer *argv)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
EuslispMessage(pointer message)
uint32_t serializationLength() const
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)
bool deps(const std::string &name, bool direct, std::vector< std::string > &deps)
pointer ROSEUS_DELETE_PARAM(register context *ctx, int n, pointer *argv)
virtual const std::type_info & getTypeInfo()
Type const & getType() const
std::vector< TopicInfo > V_TopicInfo
pointer ROSEUS_ROSPACK_PLUGINS(register context *ctx, int n, pointer *argv)
virtual ~EuslispMessage()
pointer makevector(pointer, int)
void add_module_initializer(char *, pointer(*)())
static const ServiceManagerPtr & instance()
pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx, int n, pointer *argv)
pointer mkstream(context *, pointer, pointer)
pointer XmlRpcToEusValue(register context *ctx, XmlRpc::XmlRpcValue rpc_value)
pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx, int n, pointer *argv)
pointer ROSEUS_OK(register context *ctx, int n, pointer *argv)
TimerFunction(pointer scb, pointer args)
std::map< std::string, std::string > M_string
virtual std::string getMD5Sum()
virtual const string __getServiceDataType() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
SerializedMessage request
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
ROS_INFO ROS_ERROR int pointer * argv
std::vector< std::string > V_string
pointer ROSEUS_GET_PARAM_CACHED(register context *ctx, int n, pointer *argv)
SubscriptionCallbackHelperPtr helper
ServiceCallbackHelperPtr helper
ROSCPP_DECL const std::string & getNamespace()
pointer ROSEUS_ADVERTISE(register context *ctx, int n, pointer *argv)
pointer setval(context *, pointer, pointer)
virtual bool call(ros::ServiceCallbackHelperCallParams ¶ms)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
pointer ROSEUS_ROSPACK_DEPENDS(register context *ctx, int n, pointer *argv)
pointer defvar(context *, char *, pointer, pointer)
pointer ROSEUS_SET_LOGGER_LEVEL(register context *ctx, int n, pointer *argv)
~EuslispSubscriptionCallbackHelper()
pointer K_ROSEUS_CURRENT_EXPECTED
pointer ROSEUS_GET_TOPICS(register context *ctx, int n, pointer *argv)
struct callframe * callfp
EuslispSubscriptionCallbackHelper(pointer scb, pointer args, pointer tmpl)
pointer ROSEUS_SERVICE_EXISTS(register context *ctx, int n, pointer *argv)
boost::shared_ptr< M_string > connection_header
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
pointer K_ROSEUS_DATATYPE
pointer K_ROSEUS_CURRENT_REAL
ROSCPP_DECL bool isShuttingDown()
string responseMessageDefinition
pointer K_ROSEUS_GROUPNAME
virtual const string __getServerMD5Sum() const
virtual const string __getMD5Sum() const
ROSCPP_DECL bool has(const std::string &key)
void StoreConnectionHeader(EuslispMessage *eus_msg)
SerializedMessage serializeMessage(const M &message)
pointer ROSEUS_HAS_PARAM(register context *ctx, int n, pointer *argv)
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
virtual boost::shared_ptr< EuslispMessage > createResponse()
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
EuslispMessage(const EuslispMessage &r)
string getString(pointer message, pointer method)
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)
virtual boost::shared_ptr< EuslispMessage > createRequest()
pointer defun(context *, char *, pointer, pointer(*)(), char *)
map< string, boost::shared_ptr< Publisher > > mapAdvertised
advertised topics
virtual void call(ros::SubscriptionCallbackHelperCallParams ¶m)
virtual uint8_t * deserialize(uint8_t *readPtr, uint32_t sz)
pointer stacknlist(context *, int)
boost::shared_ptr< ros::NodeHandle > node
ROSCPP_DECL bool del(const std::string &key)
pointer ROSEUS_CREATE_TIMER(register context *ctx, int n, pointer *argv)
pointer K_ROSEUS_LAST_DURATION
pointer ROSEUS_SUBSCRIBE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_SLEEP(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GETNAME(register context *ctx, int n, pointer *argv)
void crawl(std::vector< std::string > search_path, bool force)
virtual uint8_t * serialize(uint8_t *writePtr, uint32_t seqid) const
pointer makestring(char *, int)
boost::shared_array< uint8_t > buf
pointer ROSEUS_GETTOPICPUBLISHER(register context *ctx, int n, pointer *argv)
else _exit(ckintval(argv[0]))
pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx, int n, pointer *argv)
map< string, boost::shared_ptr< Subscriber > > mapSubscribed
subscribed topics
bool find(const std::string &name, std::string &path)
pointer XmlRpcToEusList(register context *ctx, XmlRpc::XmlRpcValue param_list)
pointer ROSEUS_GETNAMESPACE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GET_PORT(register context *ctx, int n, pointer *argv)
ROSCPP_DECL void shutdown()
pointer ROSEUS_SET_PARAM(register context *ctx, int n, pointer *argv)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
pointer K_ROSEUS_LAST_REAL
pointer makeobject(pointer)
ROSCPP_DECL bool getNodes(V_string &nodes)
virtual std::string getRequestMessageDefinition()
pointer ROSEUS_GET_HOST(register context *ctx, int n, pointer *argv)
eusinteger_t intval(pointer p)
virtual ros::VoidConstPtr deserialize(const ros::SubscriptionCallbackHelperDeserializeParams ¶m)
~EuslispServiceCallbackHelper()
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)
pointer ROSEUS_SPINONCE(register context *ctx, int n, pointer *argv)
ROSCPP_DECL void spinOnce()
virtual std::string getRequestDataType()
boost::shared_ptr< ros::Rate > rate
pointer ROSEUS_ADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
pointer K_FUNCTION_DOCUMENTATION
pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
boost::shared_ptr< map< string, string > > _connection_header
static void write(Stream &stream, boost::call_traits< EuslispMessage >::param_type t)
pointer ROSEUS_PUBLISH(register context *ctx, int n, pointer *argv)
pointer K_ROSEUS_SERIALIZATION_LENGTH
pointer K_ROSEUS_DEFINITION
pointer gensym(context *)
pointer ROSEUS_GET_URI(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GETNUMSUBSCRIBERS(register context *ctx, int n, pointer *argv)
byte * get_string(register pointer s)
const std::string response
map< string, Timer > mapTimered
subscribed timers
virtual std::string getResponseDataType()
pointer K_ROSEUS_LAST_EXPECTED
map< string, boost::shared_ptr< NodeHandle > > mapHandle
for grouping nodehandle
#define def_rosconsole_formatter(funcname, rosfuncname)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
pointer ROSEUS_RATE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_UNSUBSCRIBE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_ROSPACK_FIND(register context *ctx, int n, pointer *argv)