Macros | Functions
eustf.cpp File Reference
#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 <ros/init.h>
#include <ros/rate.h>
#include <ros/master.h>
#include <ros/this_node.h>
#include <ros/node_handle.h>
#include <ros/service.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
#include <tf2_ros/buffer_client.h>
#include "eus.h"
#include "defun.h"
Include dependency graph for eustf.cpp:

Go to the source code of this file.

Macros

#define class   eus_class
 
#define export   eus_export
 
#define set_ros_time(time, argv)
 
#define string   eus_string
 
#define throw   eus_throw
 
#define vector   eus_vector
 

Functions

pointer ___eustf (register context *ctx, int n, pointer *argv, pointer env)
 
pointer EUSTF_ALLFRAMESASSTRING (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_BUFFER_CLIENT (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_BUFFER_CLIENT_DISPOSE (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_CANTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_CANTRANSFORMFULL (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_CHAIN (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_CLEAR (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_FRAMEEXISTS (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_GETFRAMESTRINGS (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_GETLATERSTCOMMONTIME (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_GETPARENT (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_LOOKUPTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_LOOKUPTRANSFORMFULL (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_LOOKUPVELOCITY (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_SEND_TRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_SETEXTRAPOLATIONLIMIT (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_SETTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TFBC_CANTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TFBC_LOOKUPTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TFBC_WAITFORSERVER (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TRANSFORM_BROADCASTER (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TRANSFORM_LISTENER (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TRANSFORM_LISTENER_DISPOSE (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TRANSFORMER (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_TRANSFORMPOSE (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_WAITFORTRANSFORM (register context *ctx, int n, pointer *argv)
 
pointer EUSTF_WAITFORTRANSFORMFULL (register context *ctx, int n, pointer *argv)
 
void register_eustf ()
 

Macro Definition Documentation

#define class   eus_class

Definition at line 77 of file eustf.cpp.

#define export   eus_export

Definition at line 79 of file eustf.cpp.

#define set_ros_time (   time,
  argv 
)
Value:
if (isvector(argv) && (elmtypeof(argv)==ELM_INT)) { \
time.sec = argv->c.ivec.iv[0]; \
time.nsec = argv->c.ivec.iv[1]; \
} else { \
error(E_NOVECTOR); \
}
struct intvector ivec
union cell::cellunion c
ROS_INFO ROS_ERROR int pointer * argv
Definition: roseus.cpp:819
long iv[1]

Definition at line 109 of file eustf.cpp.

#define string   eus_string

Definition at line 81 of file eustf.cpp.

#define throw   eus_throw

Definition at line 78 of file eustf.cpp.

#define vector   eus_vector

Definition at line 80 of file eustf.cpp.

Function Documentation

pointer ___eustf ( register context ctx,
int  n,
pointer argv,
pointer  env 
)

Definition at line 822 of file eustf.cpp.

pointer EUSTF_ALLFRAMESASSTRING ( register context ctx,
int  n,
pointer argv 
)

Definition at line 127 of file eustf.cpp.

pointer EUSTF_BUFFER_CLIENT ( register context ctx,
int  n,
pointer argv 
)

Definition at line 676 of file eustf.cpp.

pointer EUSTF_BUFFER_CLIENT_DISPOSE ( register context ctx,
int  n,
pointer argv 
)

Definition at line 704 of file eustf.cpp.

pointer EUSTF_CANTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 266 of file eustf.cpp.

pointer EUSTF_CANTRANSFORMFULL ( register context ctx,
int  n,
pointer argv 
)

Definition at line 299 of file eustf.cpp.

pointer EUSTF_CHAIN ( register context ctx,
int  n,
pointer argv 
)

Definition at line 342 of file eustf.cpp.

pointer EUSTF_CLEAR ( register context ctx,
int  n,
pointer argv 
)

Definition at line 348 of file eustf.cpp.

pointer EUSTF_FRAMEEXISTS ( register context ctx,
int  n,
pointer argv 
)

Definition at line 356 of file eustf.cpp.

pointer EUSTF_GETFRAMESTRINGS ( register context ctx,
int  n,
pointer argv 
)

Definition at line 368 of file eustf.cpp.

pointer EUSTF_GETLATERSTCOMMONTIME ( register context ctx,
int  n,
pointer argv 
)

Definition at line 383 of file eustf.cpp.

pointer EUSTF_GETPARENT ( register context ctx,
int  n,
pointer argv 
)

Definition at line 604 of file eustf.cpp.

pointer EUSTF_LOOKUPTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 405 of file eustf.cpp.

pointer EUSTF_LOOKUPTRANSFORMFULL ( register context ctx,
int  n,
pointer argv 
)

Definition at line 442 of file eustf.cpp.

pointer EUSTF_LOOKUPVELOCITY ( register context ctx,
int  n,
pointer argv 
)

Definition at line 533 of file eustf.cpp.

pointer EUSTF_SEND_TRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 634 of file eustf.cpp.

pointer EUSTF_SETEXTRAPOLATIONLIMIT ( register context ctx,
int  n,
pointer argv 
)

Definition at line 592 of file eustf.cpp.

pointer EUSTF_SETTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 135 of file eustf.cpp.

pointer EUSTF_TFBC_CANTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 727 of file eustf.cpp.

pointer EUSTF_TFBC_LOOKUPTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 776 of file eustf.cpp.

pointer EUSTF_TFBC_WAITFORSERVER ( register context ctx,
int  n,
pointer argv 
)

Definition at line 712 of file eustf.cpp.

pointer EUSTF_TRANSFORM_BROADCASTER ( register context ctx,
int  n,
pointer argv 
)

Definition at line 628 of file eustf.cpp.

pointer EUSTF_TRANSFORM_LISTENER ( register context ctx,
int  n,
pointer argv 
)

Definition at line 573 of file eustf.cpp.

pointer EUSTF_TRANSFORM_LISTENER_DISPOSE ( register context ctx,
int  n,
pointer argv 
)

Definition at line 583 of file eustf.cpp.

pointer EUSTF_TRANSFORMER ( register context ctx,
int  n,
pointer argv 
)

Definition at line 118 of file eustf.cpp.

pointer EUSTF_TRANSFORMPOSE ( register context ctx,
int  n,
pointer argv 
)

Definition at line 487 of file eustf.cpp.

pointer EUSTF_WAITFORTRANSFORM ( register context ctx,
int  n,
pointer argv 
)

Definition at line 162 of file eustf.cpp.

pointer EUSTF_WAITFORTRANSFORMFULL ( register context ctx,
int  n,
pointer argv 
)

Definition at line 209 of file eustf.cpp.

void register_eustf ( )

Definition at line 90 of file eustf.cpp.



roseus
Author(s): Kei Okada
autogenerated on Fri Mar 26 2021 02:08:16