Go to the documentation of this file.
   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";
 
   99     if (isstring(
s)) 
return(
s->c.str.chars);
 
  100     if (issymbol(
s)) 
return(
s->c.sym.pname->c.str.chars);
 
  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);
 
  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",
 
  237     _message = newMessage;
 
  265   virtual uint8_t *
serialize(uint8_t *writePtr, uint32_t seqid)
 const 
  280     return writePtr + len;
 
  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();
 
  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;
 
  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;
 
  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();
 
  417   virtual const std::type_info& getTypeInfo() {
 
  420   virtual bool isConst(){
 
  435   string md5, 
datatype, requestDataType, responseDataType,
 
  436     requestMessageDefinition, responseMessageDefinition;
 
  446       if ( ccar(ccdr(scb)) != NIL ) { 
 
  447         _scb=ccar(ccdr(scb));
 
  452       ROS_ERROR(
"service callback function install error");
 
  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; }
 
  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();
 
  514     eus_res.replaceContents(r);
 
  516     pointer ret_serialize_method, ret_class;
 
  519     if (!ispointer(r) || ret_serialize_method == 
NIL) {
 
  520       ROS_ERROR(
"you may not return valid value in service callback");
 
  527     vpush(eus_res._message);    
 
  528     uint32_t serialized_length = eus_res.serializationLength();
 
  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);
 
  540     eus_res.serialize(tmp, 0);
 
  575   uint32_t options = 0;
 
  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] = 
'_';
 
  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"));
 
  691     ROS_DEBUG(
"groupname %s is already used", groupname.c_str());
 
  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__);
 
  850   if (
n > 1 && issymbol(
argv[
n-2]) && isstring(
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];
 
  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();
 
  922     ROS_ERROR(
"attempted to getNumPublishers to topic %s, which was not " \
 
  923               "previously subscribed. call (ros::subscribe \"%s\") first.",
 
  924               topicname.c_str(), topicname.c_str());
 
  939   bool bSuccess = 
false;
 
  940   map<string, boost::shared_ptr<Subscriber> >::iterator it = 
s_mapSubscribed.find(topicname);
 
  943     ret = subscriber->getTopic();
 
  964     queuesize = ckintval(
argv[2]);
 
  967     latch = (
argv[3]!=
NIL ? true : 
false);
 
  969   ROS_DEBUG(
"advertise %s %d %d", topicname.c_str(), queuesize, latch);
 
  971     ROS_WARN(
"topic %s already advertised", topicname.c_str());
 
  999   return (bSuccess?
T:
NIL);
 
 1014   bool bSuccess = 
false;
 
 1015   map<string, boost::shared_ptr<Publisher> >::iterator it = 
s_mapAdvertised.find(topicname);
 
 1019     publisher->publish(message);
 
 1024     ROS_ERROR(
"attempted to publish to topic %s, which was not " \
 
 1025               "previously advertised. call (ros::advertise \"%s\") first.",
 
 1026               topicname.c_str(), topicname.c_str());
 
 1041   bool bSuccess = 
false;
 
 1042   map<string, boost::shared_ptr<Publisher> >::iterator it = 
s_mapAdvertised.find(topicname);
 
 1045     ret = publisher->getNumSubscribers();
 
 1050     ROS_ERROR(
"attempted to getNumSubscribers to topic %s, which was not " \
 
 1051               "previously advertised. call (ros::advertise \"%s\") first.",
 
 1052               topicname.c_str(), topicname.c_str());
 
 1067   bool bSuccess = 
false;
 
 1068   map<string, boost::shared_ptr<Publisher> >::iterator it = 
s_mapAdvertised.find(topicname);
 
 1071     ret = publisher->getTopic();
 
 1098   return (bSuccess?
T:
NIL);
 
 1112   return (bSuccess?
T:
NIL);
 
 1120   bool persist = 
false;
 
 1126       persist = (
argv[2] != 
NIL ? true : 
false);
 
 1128   static std::map<std::string, ros::ServiceServerLinkPtr> service_link_cache;
 
 1129   static std::map<std::string, std::string> service_md5_cache;
 
 1141     if ( service_link_cache.find(service) != service_link_cache.end() &&
 
 1142          ( ! service_link_cache[service]->isValid() ||
 
 1143            service_md5_cache[service] !=request.
__getMD5Sum() )) {
 
 1145       service_link_cache[service].reset();
 
 1146       service_link_cache.erase(service);
 
 1147       service_md5_cache.erase(service);
 
 1150     if (service_link_cache.find(service) == service_link_cache.end()) {
 
 1152       service_md5_cache[service] = request.
__getMD5Sum();
 
 1154     link = service_link_cache[service];
 
 1159   bool bSuccess = 
true;
 
 1162   if (link && link->isValid()) {
 
 1163     bSuccess = link->call(ser_req, ser_resp);
 
 1167       } 
catch (std::exception& e) {
 
 1168         ROS_ERROR(
"Exception thrown while deserializing service call: %s", e.what());
 
 1173       cerr << __PRETTY_FUNCTION__ << endl;
 
 1174       cerr << 
"c_header == " << connection_header << endl;
 
 1175       for(map<string, string>::iterator it = connection_header->begin(); it != connection_header->end(); it++){
 
 1176         cerr << 
"            " << it->first << 
" : " << it->second << endl;
 
 1179       response._connection_header = connection_header;
 
 1189     ROS_ERROR(
"Failed to establish connection to service server");
 
 1194     ROS_ERROR(
"attempted to call service  %s, but failed ",
 
 1212   fncallback = 
argv[2];
 
 1214   if (
n >= 5 && issymbol(
argv[
n-2]) && isstring(
argv[
n-1])) {
 
 1218       map<string, boost::shared_ptr<NodeHandle > >::iterator it = 
s_mapHandle.find(groupname);
 
 1220         ROS_DEBUG(
"advertising service with groupname=%s", groupname.c_str());
 
 1221         lnode = (it->second).
get();
 
 1223         ROS_ERROR(
"Groupname \"%s\" is missing. Service %s is not advertised. Call (ros::create-nodehandle \"%s\") first.",
 
 1224                   groupname.c_str(), service.c_str(), groupname.c_str());
 
 1234     ROS_INFO(
"service %s already advertised", service.c_str());
 
 1249   aso.
datatype = (*callback->get()).getDataType();
 
 1250   aso.
md5sum = (*callback->get()).getMD5Sum();
 
 1251   aso.
req_datatype = (*callback->get()).getRequestDataType();
 
 1252   aso.
res_datatype = (*callback->get()).getResponseDataType();
 
 1273   ROS_DEBUG(
"unadvertise %s", service.c_str());
 
 1276   return (bSuccess?
T:
NIL);
 
 1283   if ( islist(argp) && islist(ccar(argp)) && !islist(ccar(ccar(argp))) ) { 
 
 1287     std::ostringstream stringstream;
 
 1288     stringstream << 
"<value><struct>";
 
 1293         if ( issymbol(ccar(
v)) ) {
 
 1295           boost::algorithm::to_lower(skey);
 
 1296           stringstream << 
"<member><name>" << skey << 
"</name><value><boolean>0</boolean></value></member>";
 
 1298         else if ( isstring(ccar(
v)) ) {
 
 1300           stringstream << 
"<member><name>" << skey << 
"</name><value><boolean>0</boolean></value></member>";
 
 1309     stringstream << 
"</struct></value>";
 
 1310     j=0; rpc_value.
fromXml(stringstream.str(), &j);
 
 1316         if ( issymbol(ccar(
v)) ) {
 
 1318           boost::algorithm::to_lower(skey);
 
 1321           rpc_value[skey] = p;
 
 1323         else if ( isstring(ccar(
v)) ) {
 
 1327           rpc_value[skey] = p;
 
 1332   } 
else if ( islist(argp) ) { 
 
 1337     i = 0; 
while ( islist(
a) ) { 
a=ccdr(
a); i++; }
 
 1342     while ( islist(
a) ) {
 
 1349   } 
else if ( isstring(argp) ) {
 
 1351   } 
else if ( isint(argp) ) {
 
 1352     rpc_value = (int)(
intval(argp));
 
 1353   } 
else if  ( isflt(argp) ) {
 
 1354     rpc_value = (double)(
fltval(argp));
 
 1355   } 
else if (argp == 
T) {
 
 1357   } 
else if (argp == 
NIL) {
 
 1359   } 
else if ( issymbol(argp) ) {
 
 1361     boost::algorithm::to_lower(
s);
 
 1362     rpc_value = 
s.c_str();
 
 1390     if ( rpc_value ) 
return T; 
else return NIL;
 
 1393     return makeflt((
double)rpc_value);
 
 1396     return makeint((
int)rpc_value);
 
 1406     for ( 
int i = 0; i < rpc_value.
size(); i++){
 
 1418     while(it !=rpc_value.
end()) {
 
 1423       ccdr(ret) = 
cons(ctx, tmp, 
NIL);
 
 1445         for ( 
int i = 0; i < param_list.
size(); i++){
 
 1447                 if ( param_list[i] ){
 
 1519       ROS_ERROR(
"unknown ros::param::get, key=%s", key.c_str());
 
 1558       ROS_ERROR(
"unknown ros::param::get, key=%s", key.c_str());
 
 1605 #if ROS_VERSION_MINIMUM(1,11,17) 
 1606   std::vector<std::string> keys;
 
 1611     for(std::vector<std::string>::iterator it = keys.begin(); it != keys.end(); it++) {
 
 1620   ROS_ERROR(
"%s : ros::rosparam::getParamNames is not implemented for roscpp %d.%d.%d",  __PRETTY_FUNCTION__, ROS_VERSION_MAJOR, ROS_VERSION_MINOR, ROS_VERSION_PATCH);
 
 1634 #ifdef ROSPACK_EXPORT 
 1635       rospack::Package *p = 
rp.get_pkg(pkg);
 
 1636       if (p!=
NULL) 
return(
makestring((
char *)p->path.c_str(),p->path.length()));
 
 1639       if (
rp.
find(pkg,path)==
true) 
return(
makestring((
char *)path.c_str(),path.length()));
 
 1641   } 
catch (runtime_error &e) {
 
 1657       std::vector<std::string> flags;
 
 1658       std::vector<rospack::Stackage*> stackages;
 
 1662       std::vector<std::string> deps;
 
 1663       if (
rp.
deps(pkg,
false,deps)) {
 
 1668         for (std::vector<std::string>::iterator it = deps.begin() ; it != deps.end(); it++) {
 
 1676   } 
catch (runtime_error &e) {
 
 1692       std::vector<std::string> flags;
 
 1693       if (
rp.
plugins(pkg, attrib, 
"", flags)) {
 
 1697           for (
size_t i = 0; i < flags.size(); i++) {
 
 1699             std::vector<std::string> parsed_string;
 
 1700             boost::algorithm::split(parsed_string, flags[i], boost::is_any_of(
" "));
 
 1705                                          makestring((
char*)value.c_str(), value.length())),
 
 1717   catch (runtime_error &e) {
 
 1727   src.assign((
char *)(
argv[0]->c.str.chars));
 
 1729   return(
makestring((
char *)dst.c_str(), dst.length()));
 
 1745   return(
makestring((
char *)ns.c_str(), ns.length()));
 
 1776   bool success = ::ros::console::set_logger_level(logger, level);
 
 1790   return makestring((
char*)host.c_str(), host.length());
 
 1806   for (ros::V_string::iterator it = nodes.begin() ; it != nodes.end(); it++) {
 
 1828   return makestring((
char*)uri.c_str(), uri.length());
 
 1844   for (ros::master::V_TopicInfo::iterator it = topics.begin() ; it != topics.end(); it++) {
 
 1848     ccdr(ret) = 
cons(ctx, tmp, 
NIL);
 
 1874       if(!memcmp(
classtab[i].def->c.cls.name->c.sym.pname->c.str.chars,(
char *)
"TIMER-EVENT",11)) {
 
 1878     if ( ! ( issymbol(_scb) || piscode(_scb) || ccar(_scb)==
LAMCLOSURE ) ) {
 
 1879       ROS_ERROR(
"%s : can't find callback function", __PRETTY_FUNCTION__);
 
 1895     while(argp!=
NIL){ ckpush(ccar(argp)); argp=ccdr(argp); argc++;}
 
 1896     vpush((
pointer)(tevent));argc++;
 
 1899     while(argc-->0)vpop();
 
 1908   bool oneshot = 
false;
 
 1916   bool check_key = 
true;
 
 1919     if (
n > 1 && issymbol(
argv[
n-2])) {
 
 1930         map<string, boost::shared_ptr<NodeHandle > >::iterator it = 
s_mapHandle.find(groupname);
 
 1932           ROS_DEBUG(
"create-timer with groupname=%s", groupname.c_str());
 
 1933           lnode = (it->second).
get();
 
 1935           ROS_ERROR(
"Groupname %s is missing. Call (ros::create-nodehandle \"%s\") first.",
 
 1936                     groupname.c_str(), groupname.c_str());
 
 1951   if (piscode(
argv[1])) { 
 
 1953     std::ostringstream stringstream;
 
 1954     stringstream << reinterpret_cast<long>(
argv[2]) << 
" ";
 
 1955     for (
int i=3; i<
n;i++)
 
 1956       stringstream << 
string((
char*)(
argv[i]->c.sym.pname->
c.
str.
chars)) << 
" ";
 
 1957     fncallname = stringstream.str();
 
 1959     if ( ccar(ccdr(
argv[1])) != 
NIL ) { 
 
 1960       fncallback=ccar(ccdr(
argv[1]));
 
 1964       std::ostringstream stringstream;
 
 1965       stringstream << reinterpret_cast<long>(
argv[1]);
 
 1966       fncallname = stringstream.str();
 
 1969     ROS_ERROR(
"subscription callback function install error");
 
 1981   ROS_DEBUG(
"create timer %s at %f (oneshot=%d) (groupname=%s)", fncallname.c_str(), period, oneshot, groupname.c_str());
 
 1994 #ifdef ROSPACK_EXPORT 
 1996   std::vector<std::string> search_path;
 
 2016          "&optional groupname  ;; spin only group\n\n" 
 2017          "Process a single round of callbacks.\n");
 
 2020   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.");
 
 2025          "write mesage to debug output\n" 
 2027          "      (ros::ros-debug \"this is error ~A\" 0)\n");
 
 2028   defun(ctx,
"ROS-INFO",
argv[0],(
pointer (*)())ROSEUS_ROSINFO, 
"write mesage to info output");
 
 2029   defun(ctx,
"ROS-WARN",
argv[0],(
pointer (*)())ROSEUS_ROSWARN, 
"write mesage to warn output");
 
 2030   defun(ctx,
"ROS-ERROR",
argv[0],(
pointer (*)())ROSEUS_ROSERROR, 
"write mesage to error output");
 
 2031   defun(ctx,
"ROS-FATAL",
argv[0],(
pointer (*)())ROSEUS_ROSFATAL, 
"write mesage to fatal output");
 
 2035          "topicname message_type callbackfunc args0 ... argsN &optional (queuesize 1) &key (:groupname groupname)\n\n" 
 2036          "Subscribe to a topic, version for class member function with bare pointer.\n" 
 2037          "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" 
 2039          "This version of subscribe is a convenience function for using function, member function, lmabda function:\n" 
 2040          "      ;; callback function\n" 
 2041          "      (defun string-cb (msg) (print (list 'cb (sys::thread-self) (send msg :data))))\n" 
 2042          "      (ros::subscribe \"chatter\" std_msgs::string #'string-cb)\n" 
 2043          "      ;; lambda function\n" 
 2044          "      (ros::subscribe \"chatter\" std_msgs::string\n" 
 2045          "                      #'(lambda (msg) (ros::ros-info\n" 
 2046          "                                       (format nil \"I heard ~A\" (send msg :data)))))\n" 
 2048          "      (defclass string-cb-class\n" 
 2049          "        :super propertied-object\n" 
 2051          "      (defmethod string-cb-class\n" 
 2052          "        (:init () (ros::subscribe \"chatter\" std_msgs::string #'send self :string-cb))\n" 
 2053          "        (:string-cb (msg) (print (list 'cb self (send msg :data)))))\n" 
 2054          "      (setq m (instance string-cb-class :init))\n" 
 2060          "topic message_class &optional (queuesize 1) (latch nil)\n" 
 2061          "Advertise a topic.\n" 
 2062          "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" 
 2063          "      (ros::advertise \"chatter\" std_msgs::string 1)");
 
 2067          "Publish a message on the topic\n" 
 2068          "      (ros::roseus \"talker\")\n" 
 2069          "      (ros::advertise \"chatter\" std_msgs::string 1)\n" 
 2070          "      (ros::rate 100)\n" 
 2071          "      (while (ros::ok)\n" 
 2072          "        (setq msg (instance std_msgs::string :init))\n" 
 2073          "        (send msg :data (format nil \"hello world ~a\" (send (ros::time-now) :sec-nsec)))\n" 
 2074          "        (ros::publish \"chatter\" msg)\n" 
 2075          "        (ros::sleep))\n");
 
 2079   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. If the timeout is -1, wait until the node is shutdown. Otherwise it wait for timeout seconds");
 
 2082          "servicename message_type &optional persist\n\n" 
 2083          "Invoke RPC service\n" 
 2084          "      (ros::roseus \"add_two_ints_client\")\n" 
 2085          "      (ros::wait-for-service \"add_two_ints\")\n" 
 2086          "      (setq req (instance roseus::AddTwoIntsRequest :init))\n" 
 2087          "      (send req :a (random 10))\n" 
 2088          "      (send req :b (random 20))\n" 
 2089          "      (setq res (ros::service-call \"add_two_ints\" req t))\n" 
 2090          "      (format t \"~d + ~d = ~d~~%\" (send req :a) (send req :b) (send res :sum))\n");
 
 2092          "servicename message_type callbackfunc args0 ... argsN &key (:groupname groupname)\n\n" 
 2093          "Advertise a service\n" 
 2094          "      (ros::advertise-service \"add_two_ints\" roseus::AddTwoInts #'add-two-ints)");
 
 2102   defun(ctx,
"SEARCH-PARAM",
argv[0],(
pointer (*)())
ROSEUS_SEARCH_PARAM, 
"key\n\n""Search up the tree for a parameter with a given key. This version defaults to starting in the current node's name.");
 
 2114          "Create ros NodeHandle with given group name. \n" 
 2116          "      (ros::roseus \"test\")\n" 
 2117          "      (ros::create-nodehandle \"mygroup\")\n" 
 2118          "      (ros::subscribe \"/test\" std_msgs::String #'(lambda (m) (print m)) :groupname \"mygroup\")\n" 
 2119          "      (ros::create-timer 0.1 #'(lambda (event) (print \"timer called\")) :groupname \"mygroup\")\n" 
 2120          "      (while (ros::ok)  (ros::spin-once \"mygroup\"))\n");
 
 2130          "period callbackfunc args0 ... argsN &key (:oneshot oneshot) (:groupname groupname)\n\n" 
 2131          "Create periodic callbacks.\n" 
 2133          "      ;; callback function\n" 
 2134          "      (defun timer-cb (event) (print \"timer callback called.\")\n" 
 2135          "      (defun oneshot-timer-cb (event) (print \"timer callback called. oneshot.\")\n" 
 2136          "      (ros::create-timer 0.1 #'timer-cb)\n" 
 2137          "      (ros::create-timer 0.1 #'oneshot-timer-cb :oneshot t)\n" 
 2138          "      ;; lambda function\n" 
 2139          "      (ros::create-timer 0.1 #'(lambda (event) (print \"timer callback called\")))\n" 
 2141          "      (defclass timer-cb-class\n" 
 2142          "        :super propertied-object\n" 
 2144          "      (defmethod timer-cb-class\n" 
 2145          "        (:init () (ros::create-timer 0.1 #'send self :timer-cb))\n" 
 2146          "        (:timer-cb (event) (print \"timer callback called\")))\n" 
 2147          "      (setq m (instance timer-cb-class :init))\n" 
 2150   pointer_update(Spevalof(
PACKAGE),p);
 
 2163     size_t pos = arg.find(
":=");
 
 2164     if (pos != std::string::npos) {
 
 2167       remappings[local_name] = external_name;
 
  
map< string, boost::shared_ptr< NodeHandle > > mapHandle
for grouping nodehandle
const std::string response
SerializedMessage response
pointer XmlRpcToEusValue(register context *ctx, XmlRpc::XmlRpcValue rpc_value)
map< string, boost::shared_ptr< ServiceServer > > mapServiced
subscribed topics
pointer ROSEUS_ROSPACK_DEPENDS(register context *ctx, int n, pointer *argv)
static void read(Stream &stream, boost::call_traits< EuslispMessage >::reference t)
const ROSCPP_DECL std::string & getNamespace()
pointer mkstream(context *, pointer, pointer)
SerializedMessage request
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
bool call(const std::string &service_name, MReq &req, MRes &res)
void deserialize(Stream &stream, boost::array< T, N > &t)
static void write(Stream &stream, boost::call_traits< EuslispMessage >::param_type t)
pointer ROSEUS_GET_PARAM_CACHED(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GET_PARAM(register context *ctx, int n, pointer *argv)
pointer ROSEUS_SLEEP(register context *ctx, int n, pointer *argv)
pointer ROSEUS_HAS_PARAM(register context *ctx, int n, pointer *argv)
pointer makeint(eusinteger_t v)
bool getSearchPathFromEnv(std::vector< std::string > &sp)
static uint32_t serializedLength(boost::call_traits< EuslispMessage >::param_type t)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
pointer ROSEUS_SERVICE_CALL(register context *ctx, int n, pointer *argv)
ROSCPP_DECL bool get(const std::string &key, bool &b)
pointer ROSEUS_GETTOPICPUBLISHER(register context *ctx, int n, pointer *argv)
void init(const M_string &remappings)
pointer defkeyword(context *, char *)
pointer ROSEUS_CREATE_NODEHANDLE(register context *ctx, int n, pointer *argv)
map< string, boost::shared_ptr< Subscriber > > mapSubscribed
subscribed topics
ROSCPP_DECL uint32_t getPort()
bool fromXml(std::string const &valueXml, int *offset)
pointer K_ROSEUS_LAST_DURATION
pointer K_ROSEUS_GROUPNAME
pointer makevector(pointer, int)
void init(const M_string &remappings)
pointer K_ROSEUS_CONNECTION_HEADER
uint32_t serializationLength(const boost::array< T, N > &t)
pointer ROSEUS_RESOLVE_NAME(register context *ctx, int n, pointer *argv)
virtual uint8_t * serialize(uint8_t *writePtr, uint32_t seqid) const
ROSCPP_DECL void spinOnce()
ROSCPP_DECL std::string clean(const std::string &name)
void add_module_initializer(char *, pointer(*)())
ROSCPP_DECL void shutdown()
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void StoreConnectionHeader(EuslispMessage *eus_msg)
bool plugins(const std::string &name, const std::string &attrib, const std::string &top, std::vector< std::string > &flags)
WallDuration last_duration
bool find(const std::string &name, std::string &path)
pointer ROSEUS_GETNAME(register context *ctx, int n, pointer *argv)
virtual const string __getDataType() const
static const ServiceManagerPtr & instance()
pointer ROSEUS_GET_PORT(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GET_NODES(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GETTOPICSUBSCRIBER(register context *ctx, int n, pointer *argv)
pointer makestring(char *, int)
ServiceCallbackHelperPtr helper
pointer ROSEUS_OK(register context *ctx, int n, pointer *argv)
void roseusSignalHandler(int sig)
pointer ROSEUS_SERVICE_EXISTS(register context *ctx, int n, pointer *argv)
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
pointer ROSEUS_UNADVERTISE(register context *ctx, int n, pointer *argv)
pointer makeobject(pointer)
pointer ROSEUS_GET_HOST(register context *ctx, int n, pointer *argv)
virtual uint8_t * deserialize(uint8_t *readPtr, uint32_t sz)
pointer ROSEUS_SUBSCRIBE(register context *ctx, int n, pointer *argv)
ROSCPP_DECL bool del(const std::string &key)
pointer ROSEUS_GETNUMPUBLISHERS(register context *ctx, int n, pointer *argv)
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
pointer K_ROSEUS_DEFINITION
void operator()(const ros::TimerEvent &event)
byte * get_string(register pointer s)
else _exit(ckintval(argv[0]))
pointer ROSEUS_SET_PARAM(register context *ctx, int n, pointer *argv)
pointer intern(context *, char *, int, pointer)
virtual const string __getServiceDataType() const
boost::shared_ptr< map< string, string > > _connection_header
void crawl(std::vector< std::string > search_path, bool force)
pointer gensym(context *)
pointer K_ROSEUS_SERIALIZATION_LENGTH
pointer defvar(context *, char *, pointer, pointer)
ROSCPP_DECL bool getCached(const std::string &key, bool &b)
pointer ROSEUS_WAIT_FOR_SERVICE(register context *ctx, int n, pointer *argv)
pointer XmlRpcToEusList(register context *ctx, XmlRpc::XmlRpcValue param_list)
pointer ROSEUS_GET_TOPICS(register context *ctx, int n, pointer *argv)
eusinteger_t intval(pointer p)
std::vector< TopicInfo > V_TopicInfo
pointer K_ROSEUS_SERIALIZE
pointer COPYOBJ(context *, int, pointer *)
pointer K_ROSEUS_DATATYPE
context * euscontexts[MAXTHREAD]
struct class_desc classtab[MAXCLASS]
ROS_INFO ROS_ERROR int pointer * argv
pointer ROSEUS_ROSPACK_FIND(register context *ctx, int n, pointer *argv)
pointer ROSEUS_GETNUMSUBSCRIBERS(register context *ctx, int n, pointer *argv)
ROSCPP_DECL bool search(const std::string &key, std::string &result)
bool depsOnDetail(const std::string &name, bool direct, std::vector< Stackage * > &deps, bool ignore_missing=false)
pointer prinx(context *, pointer, pointer)
const ROSCPP_DECL std::string & getHost()
pointer ROSEUS_UNSUBSCRIBE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_DURATION_SLEEP(register context *ctx, int n, pointer *argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
pointer ROSEUS_TIME_NOW(register context *ctx, int n, pointer *argv)
pointer ROSEUS_DELETE_PARAM(register context *ctx, int n, pointer *argv)
pointer ROSEUS_CREATE_TIMER(register context *ctx, int n, pointer *argv)
ValueStruct::iterator iterator
pointer ROSEUS_RATE(register context *ctx, int n, pointer *argv)
pointer K_ROSEUS_LAST_EXPECTED
pointer ROSEUS_ROSPACK_PLUGINS(register context *ctx, int n, pointer *argv)
const Type & getType() const
pointer ROSEUS_LIST_PARAM(register context *ctx, int n, pointer *argv)
struct ros::TimerEvent::@0 profile
bool deps(const std::string &name, bool direct, std::vector< std::string > &deps)
pointer ROSEUS_SPIN(register context *ctx, int n, pointer *argv)
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
pointer ROSEUS_ADVERTISE(register context *ctx, int n, pointer *argv)
ROSCPP_DECL void set(const std::string &key, bool b)
virtual ~EuslispMessage()
const ROSCPP_DECL std::string & getName()
pointer K_ROSEUS_CURRENT_EXPECTED
ROSCPP_DECL bool getNodes(V_string &nodes)
virtual const string __getMD5Sum() const
map< string, boost::shared_ptr< Publisher > > mapAdvertised
advertised topics
pointer ROSEUS_SEARCH_PARAM(register context *ctx, int n, pointer *argv)
pointer SETSLOT(context *, int, pointer *)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
pointer findmethod(context *, pointer, pointer, pointer *)
string getString(pointer message, pointer method)
pointer makepkg(context *, pointer, pointer, pointer)
void EusValueToXmlRpc(register context *ctx, pointer argp, XmlRpc::XmlRpcValue &rpc_value)
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
pointer stacknlist(context *, int)
pointer ROSEUS_UNADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
uint32_t serializationLength() const
SerializedMessage serializeMessage(const M &message)
ROSCPP_DECL bool isShuttingDown()
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
pointer defun(context *, char *, pointer, pointer(*)(), char *)
TimerFunction(pointer scb, pointer args)
pointer ROSEUS_ADVERTISE_SERVICE(register context *ctx, int n, pointer *argv)
struct callframe * callfp
boost::shared_ptr< ros::NodeHandle > node
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
T param(const std::string ¶m_name, const T &default_val)
map< string, Timer > mapTimered
subscribed timers
pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env)
EuslispMessage(pointer message)
virtual void replaceContents(pointer newMessage)
static RoseusStaticData s_staticdata
std::vector< std::string > V_string
ROSCPP_DECL bool has(const std::string &key)
pointer ufuncall(context *, pointer, pointer, pointer, struct bindframe *, int)
boost::shared_ptr< ros::Rate > rate
pointer ROSEUS_GET_URI(register context *ctx, int n, pointer *argv)
SubscriptionCallbackHelperPtr helper
pointer setval(context *, pointer, pointer)
pointer ROSEUS_GETNAMESPACE(register context *ctx, int n, pointer *argv)
pointer ROSEUS_PUBLISH(register context *ctx, int n, pointer *argv)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
const ROSCPP_DECL std::string & getURI()
pointer K_ROSEUS_RESPONSE
pointer ROSEUS(register context *ctx, int n, pointer *argv)
pointer K_ROSEUS_DESERIALIZE
virtual const string __getServerMD5Sum() const
pointer K_ROSEUS_LAST_REAL
pointer K_FUNCTION_DOCUMENTATION
pointer K_ROSEUS_CURRENT_REAL
void deserializeMessage(const SerializedMessage &m, M &message)
virtual const string __getMessageDefinition() const
boost::shared_array< uint8_t > buf
pointer ROSEUS_SPINONCE(register context *ctx, int n, pointer *argv)
int getInteger(pointer message, pointer method)
#define def_rosconsole_formatter(funcname, rosfuncname)
pointer ROSEUS_SET_LOGGER_LEVEL(register context *ctx, int n, pointer *argv)
boost::shared_ptr< M_string > connection_header
std::map< std::string, std::string > M_string
EuslispMessage(const EuslispMessage &r)
roseus
Author(s): Kei Okada 
autogenerated on Sat Feb 15 2025 03:34:14