#include <Python.h>#include <tf2/buffer_core.h>#include <tf2/exceptions.h>
Go to the source code of this file.
| Classes | |
| struct | buffer_core_t | 
| Defines | |
| #define | WRAP(x) | 
| Functions | |
| static PyObject * | allFramesAsString (PyObject *self, PyObject *args) | 
| static PyObject * | allFramesAsYAML (PyObject *self, PyObject *args) | 
| static int | BufferCore_init (PyObject *self, PyObject *args, PyObject *kw) | 
| static PyObject * | canTransformCore (PyObject *self, PyObject *args, PyObject *kw) | 
| static PyObject * | canTransformFullCore (PyObject *self, PyObject *args, PyObject *kw) | 
| static PyObject * | clear (PyObject *self, PyObject *args) | 
| void | init_tf2 () | 
| static PyObject * | lookupTransformCore (PyObject *self, PyObject *args, PyObject *kw) | 
| static PyObject * | lookupTransformFullCore (PyObject *self, PyObject *args, PyObject *kw) | 
| static PyObject * | PyObject_BorrowAttrString (PyObject *o, const char *name) | 
| static int | rosduration_converter (PyObject *obj, ros::Duration *rt) | 
| static int | rostime_converter (PyObject *obj, ros::Time *rt) | 
| static PyObject * | setTransform (PyObject *self, PyObject *args) | 
| static PyObject * | setTransformStatic (PyObject *self, PyObject *args) | 
| static PyObject * | transform_converter (const geometry_msgs::TransformStamped *transform) | 
| Variables | |
| static struct PyMethodDef | buffer_core_methods [] | 
| static PyTypeObject | buffer_core_Type | 
| static PyMethodDef | module_methods [] | 
| static PyObject * | pModulegeometrymsgs = NULL | 
| static PyObject * | pModulerospy = NULL | 
| static PyObject * | tf2_connectivityexception = NULL | 
| static PyObject * | tf2_exception = NULL | 
| static PyObject * | tf2_extrapolationexception = NULL | 
| static PyObject * | tf2_invalidargumentexception = NULL | 
| static PyObject * | tf2_lookupexception = NULL | 
| static PyObject * | tf2_timeoutexception = NULL | 
| #define WRAP | ( | x | ) | 
Definition at line 8 of file tf2_py.cpp.
| static PyObject* allFramesAsString | ( | PyObject * | self, | 
| PyObject * | args | ||
| ) |  [static] | 
Definition at line 189 of file tf2_py.cpp.
| static PyObject* allFramesAsYAML | ( | PyObject * | self, | 
| PyObject * | args | ||
| ) |  [static] | 
Definition at line 183 of file tf2_py.cpp.
| static int BufferCore_init | ( | PyObject * | self, | 
| PyObject * | args, | ||
| PyObject * | kw | ||
| ) |  [static] | 
Definition at line 159 of file tf2_py.cpp.
| static PyObject* canTransformCore | ( | PyObject * | self, | 
| PyObject * | args, | ||
| PyObject * | kw | ||
| ) |  [static] | 
Definition at line 195 of file tf2_py.cpp.
| static PyObject* canTransformFullCore | ( | PyObject * | self, | 
| PyObject * | args, | ||
| PyObject * | kw | ||
| ) |  [static] | 
Definition at line 210 of file tf2_py.cpp.
| static PyObject* clear | ( | PyObject * | self, | 
| PyObject * | args | ||
| ) |  [static] | 
Definition at line 440 of file tf2_py.cpp.
| void init_tf2 | ( | ) | 
Definition at line 492 of file tf2_py.cpp.
| static PyObject* lookupTransformCore | ( | PyObject * | self, | 
| PyObject * | args, | ||
| PyObject * | kw | ||
| ) |  [static] | 
Definition at line 289 of file tf2_py.cpp.
| static PyObject* lookupTransformFullCore | ( | PyObject * | self, | 
| PyObject * | args, | ||
| PyObject * | kw | ||
| ) |  [static] | 
Definition at line 309 of file tf2_py.cpp.
| static PyObject* PyObject_BorrowAttrString | ( | PyObject * | o, | 
| const char * | name | ||
| ) |  [static] | 
Definition at line 64 of file tf2_py.cpp.
| static int rosduration_converter | ( | PyObject * | obj, | 
| ros::Duration * | rt | ||
| ) |  [static] | 
Definition at line 146 of file tf2_py.cpp.
| static int rostime_converter | ( | PyObject * | obj, | 
| ros::Time * | rt | ||
| ) |  [static] | 
Definition at line 133 of file tf2_py.cpp.
| static PyObject* setTransform | ( | PyObject * | self, | 
| PyObject * | args | ||
| ) |  [static] | 
Definition at line 377 of file tf2_py.cpp.
| static PyObject* setTransformStatic | ( | PyObject * | self, | 
| PyObject * | args | ||
| ) |  [static] | 
Definition at line 408 of file tf2_py.cpp.
| static PyObject* transform_converter | ( | const geometry_msgs::TransformStamped * | transform | ) |  [static] | 
Definition at line 72 of file tf2_py.cpp.
| struct PyMethodDef buffer_core_methods[]  [static] | 
{
  {"all_frames_as_yaml", allFramesAsYAML, METH_VARARGS},
  {"all_frames_as_string", allFramesAsString, METH_VARARGS},
  {"set_transform", setTransform, METH_VARARGS},
  {"set_transform_static", setTransformStatic, METH_VARARGS},
  {"can_transform_core", (PyCFunction)canTransformCore, METH_KEYWORDS},
  {"can_transform_full_core", (PyCFunction)canTransformFullCore, METH_KEYWORDS},
  
  {"clear", (PyCFunction)clear, METH_KEYWORDS},
  
  
  
  {"lookup_transform_core", (PyCFunction)lookupTransformCore, METH_KEYWORDS},
  {"lookup_transform_full_core", (PyCFunction)lookupTransformFullCore, METH_KEYWORDS},
  
  
  
  {NULL,          NULL}
}
Definition at line 466 of file tf2_py.cpp.
| PyTypeObject buffer_core_Type  [static] | 
 {
  PyObject_HEAD_INIT(&PyType_Type)
  0,                               
  "_tf2.BufferCore",                
  sizeof(buffer_core_t),           
}
Definition at line 57 of file tf2_py.cpp.
| PyMethodDef module_methods[]  [static] | 
 {
  
  {0, 0, 0},
}
Definition at line 487 of file tf2_py.cpp.
| PyObject* pModulegeometrymsgs = NULL  [static] | 
Definition at line 47 of file tf2_py.cpp.
| PyObject* pModulerospy = NULL  [static] | 
Definition at line 46 of file tf2_py.cpp.
| PyObject* tf2_connectivityexception = NULL  [static] | 
Definition at line 49 of file tf2_py.cpp.
| PyObject* tf2_exception = NULL  [static] | 
Definition at line 48 of file tf2_py.cpp.
| PyObject * tf2_extrapolationexception = NULL  [static] | 
Definition at line 49 of file tf2_py.cpp.
| PyObject * tf2_invalidargumentexception = NULL  [static] | 
Definition at line 50 of file tf2_py.cpp.
| PyObject * tf2_lookupexception = NULL  [static] | 
Definition at line 49 of file tf2_py.cpp.
| PyObject * tf2_timeoutexception = NULL  [static] | 
Definition at line 50 of file tf2_py.cpp.