diff --git a/roseus/eustf.cpp b/roseus/eustf.cpp index 5b6eb83d6..ea33cf886 100644 --- a/roseus/eustf.cpp +++ b/roseus/eustf.cpp @@ -89,7 +89,7 @@ extern "C" { pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env); void register_eustf(){ char modname[] = "___eustf"; - return add_module_initializer(modname, (pointer (*)())___eustf);} + return add_module_initializer(modname, (pointer (*)(context*, int, pointer*))___eustf);} } #undef class @@ -836,39 +836,39 @@ pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env) exit(2); } Spevalof(PACKAGE)=rospkg; - defun(ctx,"EUSTF-TRANSFORMER",argv[0],(pointer (*)())EUSTF_TRANSFORMER,"A Class which provides coordinate transforms between any two frames in a system"); - defun(ctx,"EUSTF-ALL-FRAMES-AS-STRING",argv[0],(pointer (*)())EUSTF_ALLFRAMESASSTRING,"A way to see what frames have been cached Useful for debugging"); - defun(ctx,"EUSTF-SET-TRANSFORM",argv[0],(pointer (*)())EUSTF_SETTRANSFORM,"Add transform information to the tf data structure"); - defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORM,"Block until a transform is possible or it times out"); - defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORMFULL,"Block until a transform is possible or it times out"); - defun(ctx,"EUSTF-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_CANTRANSFORM,"Test if a transform is possible"); - defun(ctx,"EUSTF-CAN-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_CANTRANSFORMFULL,"Test if a transform is possible"); - defun(ctx,"EUSTF-CHAIN",argv[0],(pointer (*)())EUSTF_CHAIN,"Debugging function that will print the spanning chain of transforms"); - defun(ctx,"EUSTF-CLEAR",argv[0],(pointer (*)())EUSTF_CLEAR,"Clear all data"); - defun(ctx,"EUSTF-FRAME-EXISTS",argv[0],(pointer (*)())EUSTF_FRAMEEXISTS,"Check if a frame exists in the tree"); - defun(ctx,"EUSTF-GET-FRAME-STRINGS",argv[0],(pointer (*)())EUSTF_GETFRAMESTRINGS,"A way to get a std::vector of available frame ids"); - defun(ctx,"EUSTF-GET-LATEST-COMMON-TIME",argv[0],(pointer (*)())EUSTF_GETLATERSTCOMMONTIME,"Return the latest rostime which is common across the spanning set zero if fails to cross"); - defun(ctx,"EUSTF-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID"); - defun(ctx,"EUSTF-LOOKUP-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORMFULL,"Get the transform between two frames by frame ID"); - defun(ctx,"EUSTF-TRANSFORM-POSE",argv[0],(pointer (*)())EUSTF_TRANSFORMPOSE,"Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument"); - defun(ctx,"EUSTF-LOOKUP-VELOCITY",argv[0],(pointer (*)())EUSTF_LOOKUPVELOCITY,"Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point"); + defun(ctx,"EUSTF-TRANSFORMER",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TRANSFORMER,"A Class which provides coordinate transforms between any two frames in a system"); + defun(ctx,"EUSTF-ALL-FRAMES-AS-STRING",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_ALLFRAMESASSTRING,"A way to see what frames have been cached Useful for debugging"); + defun(ctx,"EUSTF-SET-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_SETTRANSFORM,"Add transform information to the tf data structure"); + defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_WAITFORTRANSFORM,"Block until a transform is possible or it times out"); + defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM-FULL",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_WAITFORTRANSFORMFULL,"Block until a transform is possible or it times out"); + defun(ctx,"EUSTF-CAN-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_CANTRANSFORM,"Test if a transform is possible"); + defun(ctx,"EUSTF-CAN-TRANSFORM-FULL",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_CANTRANSFORMFULL,"Test if a transform is possible"); + defun(ctx,"EUSTF-CHAIN",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_CHAIN,"Debugging function that will print the spanning chain of transforms"); + defun(ctx,"EUSTF-CLEAR",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_CLEAR,"Clear all data"); + defun(ctx,"EUSTF-FRAME-EXISTS",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_FRAMEEXISTS,"Check if a frame exists in the tree"); + defun(ctx,"EUSTF-GET-FRAME-STRINGS",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_GETFRAMESTRINGS,"A way to get a std::vector of available frame ids"); + defun(ctx,"EUSTF-GET-LATEST-COMMON-TIME",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_GETLATERSTCOMMONTIME,"Return the latest rostime which is common across the spanning set zero if fails to cross"); + defun(ctx,"EUSTF-LOOKUP-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID"); + defun(ctx,"EUSTF-LOOKUP-TRANSFORM-FULL",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_LOOKUPTRANSFORMFULL,"Get the transform between two frames by frame ID"); + defun(ctx,"EUSTF-TRANSFORM-POSE",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TRANSFORMPOSE,"Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument"); + defun(ctx,"EUSTF-LOOKUP-VELOCITY",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_LOOKUPVELOCITY,"Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point"); /* */ - defun(ctx,"EUSTF-TRANSFORM-LISTENER",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER,"This class inherits from Transformer and automatically subscribes to ROS transform messages"); - defun(ctx,"EUSTF-TRANSFORM-LISTENER-DISPOSE",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER_DISPOSE,"Destructor for TransformListener"); + defun(ctx,"EUSTF-TRANSFORM-LISTENER",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TRANSFORM_LISTENER,"This class inherits from Transformer and automatically subscribes to ROS transform messages"); + defun(ctx,"EUSTF-TRANSFORM-LISTENER-DISPOSE",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TRANSFORM_LISTENER_DISPOSE,"Destructor for TransformListener"); /* */ - defun(ctx,"EUSTF-SET-EXTRAPOLATION-LIMIT",argv[0],(pointer (*)())EUSTF_SETEXTRAPOLATIONLIMIT,"Set the distance which tf is allow to extrapolate"); - defun(ctx,"EUSTF-GET-PARENT",argv[0],(pointer (*)())EUSTF_GETPARENT,"Fill the parent of a frame"); + defun(ctx,"EUSTF-SET-EXTRAPOLATION-LIMIT",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_SETEXTRAPOLATIONLIMIT,"Set the distance which tf is allow to extrapolate"); + defun(ctx,"EUSTF-GET-PARENT",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_GETPARENT,"Fill the parent of a frame"); /* */ - defun(ctx,"EUSTF-TRANSFORM-BROADCASTER",argv[0],(pointer (*)())EUSTF_TRANSFORM_BROADCASTER,"This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message"); - defun(ctx,"EUSTF-SEND-TRANSFORM",argv[0],(pointer (*)())EUSTF_SEND_TRANSFORM,"Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already"); + defun(ctx,"EUSTF-TRANSFORM-BROADCASTER",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TRANSFORM_BROADCASTER,"This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message"); + defun(ctx,"EUSTF-SEND-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_SEND_TRANSFORM,"Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already"); /* tf2 */ - defun(ctx,"EUSTF-BUFFER-CLIENT",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT,"Action client-based implementation of the tf2_ros::BufferInterface abstract data type. BufferClient uses actionlib to coordinate waiting for available transforms."); - defun(ctx,"EUSTF-BUFFER-CLIENT-DISPOSE",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT_DISPOSE,"tf2 BufferClient destructor"); - defun(ctx,"EUSTF-TF2-WAIT-FOR-SERVER",argv[0],(pointer (*)())EUSTF_TFBC_WAITFORSERVER,"Block until the action server is ready to respond to requests"); - defun(ctx,"EUSTF-TF2-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_CANTRANSFORM,"Test if a transform is possible"); - defun(ctx,"EUSTF-TF2-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID"); + defun(ctx,"EUSTF-BUFFER-CLIENT",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_BUFFER_CLIENT,"Action client-based implementation of the tf2_ros::BufferInterface abstract data type. BufferClient uses actionlib to coordinate waiting for available transforms."); + defun(ctx,"EUSTF-BUFFER-CLIENT-DISPOSE",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_BUFFER_CLIENT_DISPOSE,"tf2 BufferClient destructor"); + defun(ctx,"EUSTF-TF2-WAIT-FOR-SERVER",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TFBC_WAITFORSERVER,"Block until the action server is ready to respond to requests"); + defun(ctx,"EUSTF-TF2-CAN-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TFBC_CANTRANSFORM,"Test if a transform is possible"); + defun(ctx,"EUSTF-TF2-LOOKUP-TRANSFORM",argv[0],(pointer (*)(context*, int, pointer*))EUSTF_TFBC_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID"); pointer_update(Spevalof(PACKAGE),p); return 0; diff --git a/roseus/roseus.cpp b/roseus/roseus.cpp index 017869c23..d060da53b 100644 --- a/roseus/roseus.cpp +++ b/roseus/roseus.cpp @@ -92,7 +92,7 @@ extern "C" { pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env); void register_roseus(){ char modname[] = "___roseus"; - return add_module_initializer(modname, (pointer (*)())___roseus);} + return add_module_initializer(modname, (pointer (*)(context*, int, 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){ @@ -2010,28 +2010,28 @@ pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env) QROSWARN=defvar(ctx,"*ROSWARN*",makeint(3),rospkg); QROSERROR=defvar(ctx,"*ROSERROR*",makeint(4),rospkg); QROSFATAL=defvar(ctx,"*ROSFATAL*",makeint(5),rospkg); - defun(ctx,"SPIN",argv[0],(pointer (*)())ROSEUS_SPIN, "Enter simple event loop"); + defun(ctx,"SPIN",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SPIN, "Enter simple event loop"); - defun(ctx,"SPIN-ONCE",argv[0],(pointer (*)())ROSEUS_SPINONCE, + defun(ctx,"SPIN-ONCE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SPINONCE, "&optional groupname ;; spin only group\n\n" "Process a single round of callbacks.\n"); - defun(ctx,"TIME-NOW-RAW",argv[0],(pointer (*)())ROSEUS_TIME_NOW, ""); - defun(ctx,"RATE",argv[0],(pointer (*)())ROSEUS_RATE, "frequency\n\n" "Construct ros timer for periodic sleeps"); - 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."); - defun(ctx,"DURATION-SLEEP",argv[0],(pointer (*)())ROSEUS_DURATION_SLEEP, "second\n\nSleeps for amount of the time specified by this duration."); - defun(ctx,"OK",argv[0],(pointer (*)())ROSEUS_OK, "Check whether it's time to exit. "); + defun(ctx,"TIME-NOW-RAW",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_TIME_NOW, ""); + defun(ctx,"RATE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_RATE, "frequency\n\n" "Construct ros timer for periodic sleeps"); + defun(ctx,"SLEEP",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SLEEP, "Sleeps for any leftover time in a cycle. Calculated from the last time sleep, reset, or the constructor was called."); + defun(ctx,"DURATION-SLEEP",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_DURATION_SLEEP, "second\n\nSleeps for amount of the time specified by this duration."); + defun(ctx,"OK",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_OK, "Check whether it's time to exit. "); - defun(ctx,"ROS-DEBUG",argv[0],(pointer (*)())ROSEUS_ROSDEBUG, + defun(ctx,"ROS-DEBUG",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSDEBUG, "write mesage to debug output\n" "\n" " (ros::ros-debug \"this is error ~A\" 0)\n"); - defun(ctx,"ROS-INFO",argv[0],(pointer (*)())ROSEUS_ROSINFO, "write mesage to info output"); - defun(ctx,"ROS-WARN",argv[0],(pointer (*)())ROSEUS_ROSWARN, "write mesage to warn output"); - defun(ctx,"ROS-ERROR",argv[0],(pointer (*)())ROSEUS_ROSERROR, "write mesage to error output"); - defun(ctx,"ROS-FATAL",argv[0],(pointer (*)())ROSEUS_ROSFATAL, "write mesage to fatal output"); - defun(ctx,"EXIT",argv[0],(pointer (*)())ROSEUS_EXIT, "Exit ros clinet"); + defun(ctx,"ROS-INFO",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSINFO, "write mesage to info output"); + defun(ctx,"ROS-WARN",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSWARN, "write mesage to warn output"); + defun(ctx,"ROS-ERROR",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSERROR, "write mesage to error output"); + defun(ctx,"ROS-FATAL",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSFATAL, "write mesage to fatal output"); + defun(ctx,"EXIT",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_EXIT, "Exit ros clinet"); - defun(ctx,"SUBSCRIBE",argv[0],(pointer (*)())ROSEUS_SUBSCRIBE, + defun(ctx,"SUBSCRIBE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SUBSCRIBE, "topicname message_type callbackfunc args0 ... argsN &optional (queuesize 1) &key (:groupname groupname)\n\n" "Subscribe to a topic, version for class member function with bare pointer.\n" "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" @@ -2053,16 +2053,16 @@ pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env) " (:string-cb (msg) (print (list 'cb self (send msg :data)))))\n" " (setq m (instance string-cb-class :init))\n" ); - defun(ctx,"UNSUBSCRIBE",argv[0],(pointer (*)())ROSEUS_UNSUBSCRIBE, "topicname\n\n""Unsubscribe topic"); - defun(ctx,"GET-NUM-PUBLISHERS",argv[0],(pointer (*)())ROSEUS_GETNUMPUBLISHERS, "Returns the number of publishers this subscriber is connected to. "); - defun(ctx,"GET-TOPIC-SUBSCRIBER",argv[0],(pointer (*)())ROSEUS_GETTOPICSUBSCRIBER, "topicname\n\n""Retuns the name of topic if it already subscribed"); - defun(ctx,"ADVERTISE",argv[0],(pointer (*)())ROSEUS_ADVERTISE, + defun(ctx,"UNSUBSCRIBE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_UNSUBSCRIBE, "topicname\n\n""Unsubscribe topic"); + defun(ctx,"GET-NUM-PUBLISHERS",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETNUMPUBLISHERS, "Returns the number of publishers this subscriber is connected to. "); + defun(ctx,"GET-TOPIC-SUBSCRIBER",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETTOPICSUBSCRIBER, "topicname\n\n""Retuns the name of topic if it already subscribed"); + defun(ctx,"ADVERTISE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ADVERTISE, "topic message_class &optional (queuesize 1) (latch nil)\n" "Advertise a topic.\n" "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" " (ros::advertise \"chatter\" std_msgs::string 1)"); - defun(ctx,"UNADVERTISE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE, "Unadvertise topic"); - defun(ctx,"PUBLISH",argv[0],(pointer (*)())ROSEUS_PUBLISH, + defun(ctx,"UNADVERTISE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_UNADVERTISE, "Unadvertise topic"); + defun(ctx,"PUBLISH",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_PUBLISH, "topic message\n\n" "Publish a message on the topic\n" " (ros::roseus \"talker\")\n" @@ -2073,12 +2073,12 @@ pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env) " (send msg :data (format nil \"hello world ~a\" (send (ros::time-now) :sec-nsec)))\n" " (ros::publish \"chatter\" msg)\n" " (ros::sleep))\n"); - defun(ctx,"GET-NUM-SUBSCRIBERS",argv[0],(pointer (*)())ROSEUS_GETNUMSUBSCRIBERS, "Retuns number of subscribers this publish is connected to"); - defun(ctx,"GET-TOPIC-PUBLISHER",argv[0],(pointer (*)())ROSEUS_GETTOPICPUBLISHER, "topicname\n\n""Retuns the name of topic if it already published"); + defun(ctx,"GET-NUM-SUBSCRIBERS",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETNUMSUBSCRIBERS, "Retuns number of subscribers this publish is connected to"); + defun(ctx,"GET-TOPIC-PUBLISHER",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETTOPICPUBLISHER, "topicname\n\n""Retuns the name of topic if it already published"); - 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"); - defun(ctx,"SERVICE-EXISTS", argv[0], (pointer (*)())ROSEUS_SERVICE_EXISTS, "servicename\n\n""Checks if a service is both advertised and available."); - defun(ctx,"SERVICE-CALL",argv[0],(pointer (*)())ROSEUS_SERVICE_CALL, + defun(ctx,"WAIT-FOR-SERVICE",argv[0],(pointer (*)(context*, int, 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"); + defun(ctx,"SERVICE-EXISTS", argv[0], (pointer (*)(context*, int, pointer*))ROSEUS_SERVICE_EXISTS, "servicename\n\n""Checks if a service is both advertised and available."); + defun(ctx,"SERVICE-CALL",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SERVICE_CALL, "servicename message_type &optional persist\n\n" "Invoke RPC service\n" " (ros::roseus \"add_two_ints_client\")\n" @@ -2088,29 +2088,29 @@ pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env) " (send req :b (random 20))\n" " (setq res (ros::service-call \"add_two_ints\" req t))\n" " (format t \"~d + ~d = ~d~~%\" (send req :a) (send req :b) (send res :sum))\n"); - defun(ctx,"ADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_ADVERTISE_SERVICE, + defun(ctx,"ADVERTISE-SERVICE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ADVERTISE_SERVICE, "servicename message_type callbackfunc args0 ... argsN &key (:groupname groupname)\n\n" "Advertise a service\n" " (ros::advertise-service \"add_two_ints\" roseus::AddTwoInts #'add-two-ints)"); - defun(ctx,"UNADVERTISE-SERVICE",argv[0],(pointer (*)())ROSEUS_UNADVERTISE_SERVICE, "Unadvertise service"); - - defun(ctx,"SET-PARAM",argv[0],(pointer (*)())ROSEUS_SET_PARAM, "key value\n\n""Set parameter"); - defun(ctx,"GET-PARAM",argv[0],(pointer (*)())ROSEUS_GET_PARAM, "key\n\n""Get parameter"); - defun(ctx,"GET-PARAM-CACHED",argv[0],(pointer (*)())ROSEUS_GET_PARAM_CACHED, "Get chached parameter"); - defun(ctx,"HAS-PARAM",argv[0],(pointer (*)())ROSEUS_HAS_PARAM, "Check whether a parameter exists on the parameter server."); - defun(ctx,"DELETE-PARAM",argv[0],(pointer (*)())ROSEUS_DELETE_PARAM, "key\n\n""Delete parameter from server"); - 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."); - defun(ctx,"LIST-PARAM",argv[0],(pointer (*)())ROSEUS_LIST_PARAM, "Get the list of all the parameters in the server"); - - defun(ctx,"ROSPACK-FIND",argv[0],(pointer (*)())ROSEUS_ROSPACK_FIND, "Returns ros package path"); - defun(ctx,"ROSPACK-PLUGINS",argv[0],(pointer (*)())ROSEUS_ROSPACK_PLUGINS, "Returns plugins of ros packages"); - defun(ctx,"ROSPACK-DEPENDS",argv[0],(pointer (*)())ROSEUS_ROSPACK_DEPENDS, "Returns ros package dependencies list"); - defun(ctx,"RESOLVE-NAME",argv[0],(pointer (*)())ROSEUS_RESOLVE_NAME, "Returns ros resolved name"); - defun(ctx,"GET-NAME",argv[0],(pointer (*)())ROSEUS_GETNAME, "Returns current node name"); - defun(ctx,"GET-NAMESPACE",argv[0],(pointer (*)())ROSEUS_GETNAMESPACE, "Returns current node name space"); - - defun(ctx,"ROSEUS-RAW",argv[0],(pointer (*)())ROSEUS, ""); - defun(ctx,"CREATE-NODEHANDLE", argv[0], (pointer (*)())ROSEUS_CREATE_NODEHANDLE, "groupname &optional namespace ;;\n\n" + defun(ctx,"UNADVERTISE-SERVICE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_UNADVERTISE_SERVICE, "Unadvertise service"); + + defun(ctx,"SET-PARAM",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SET_PARAM, "key value\n\n""Set parameter"); + defun(ctx,"GET-PARAM",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_PARAM, "key\n\n""Get parameter"); + defun(ctx,"GET-PARAM-CACHED",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_PARAM_CACHED, "Get chached parameter"); + defun(ctx,"HAS-PARAM",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_HAS_PARAM, "Check whether a parameter exists on the parameter server."); + defun(ctx,"DELETE-PARAM",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_DELETE_PARAM, "key\n\n""Delete parameter from server"); + defun(ctx,"SEARCH-PARAM",argv[0],(pointer (*)(context*, int, 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."); + defun(ctx,"LIST-PARAM",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_LIST_PARAM, "Get the list of all the parameters in the server"); + + defun(ctx,"ROSPACK-FIND",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSPACK_FIND, "Returns ros package path"); + defun(ctx,"ROSPACK-PLUGINS",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSPACK_PLUGINS, "Returns plugins of ros packages"); + defun(ctx,"ROSPACK-DEPENDS",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_ROSPACK_DEPENDS, "Returns ros package dependencies list"); + defun(ctx,"RESOLVE-NAME",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_RESOLVE_NAME, "Returns ros resolved name"); + defun(ctx,"GET-NAME",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETNAME, "Returns current node name"); + defun(ctx,"GET-NAMESPACE",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GETNAMESPACE, "Returns current node name space"); + + defun(ctx,"ROSEUS-RAW",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS, ""); + defun(ctx,"CREATE-NODEHANDLE", argv[0], (pointer (*)(context*, int, pointer*))ROSEUS_CREATE_NODEHANDLE, "groupname &optional namespace ;;\n\n" "Create ros NodeHandle with given group name. \n" "\n" " (ros::roseus \"test\")\n" @@ -2118,15 +2118,15 @@ pointer ___roseus(register context *ctx, int n, pointer *argv, pointer env) " (ros::subscribe \"/test\" std_msgs::String #'(lambda (m) (print m)) :groupname \"mygroup\")\n" " (ros::create-timer 0.1 #'(lambda (event) (print \"timer called\")) :groupname \"mygroup\")\n" " (while (ros::ok) (ros::spin-once \"mygroup\"))\n"); - defun(ctx,"SET-LOGGER-LEVEL",argv[0],(pointer (*)())ROSEUS_SET_LOGGER_LEVEL, ""); + defun(ctx,"SET-LOGGER-LEVEL",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_SET_LOGGER_LEVEL, ""); - defun(ctx,"GET-HOST",argv[0],(pointer (*)())ROSEUS_GET_HOST, "Get the hostname where the master runs."); - defun(ctx,"GET-NODES",argv[0],(pointer (*)())ROSEUS_GET_NODES, "Retreives the currently-known list of nodes from the master."); - defun(ctx,"GET-PORT",argv[0],(pointer (*)())ROSEUS_GET_PORT, "Get the port where the master runs."); - defun(ctx,"GET-URI",argv[0],(pointer (*)())ROSEUS_GET_URI, "Get the full URI to the master "); - defun(ctx,"GET-TOPICS",argv[0],(pointer (*)())ROSEUS_GET_TOPICS, "Get the list of topics that are being published by all nodes."); + defun(ctx,"GET-HOST",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_HOST, "Get the hostname where the master runs."); + defun(ctx,"GET-NODES",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_NODES, "Retreives the currently-known list of nodes from the master."); + defun(ctx,"GET-PORT",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_PORT, "Get the port where the master runs."); + defun(ctx,"GET-URI",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_URI, "Get the full URI to the master "); + defun(ctx,"GET-TOPICS",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_GET_TOPICS, "Get the list of topics that are being published by all nodes."); - defun(ctx,"CREATE-TIMER",argv[0],(pointer (*)())ROSEUS_CREATE_TIMER, + defun(ctx,"CREATE-TIMER",argv[0],(pointer (*)(context*, int, pointer*))ROSEUS_CREATE_TIMER, "period callbackfunc args0 ... argsN &key (:oneshot oneshot) (:groupname groupname)\n\n" "Create periodic callbacks.\n" "\n"