#include <Python.h>
#include <tf2/buffer_core.h>
#include <tf2/exceptions.h>
#include "python_compat.h"
Go to the source code of this file.
Classes | |
struct | buffer_core_t |
Defines | |
#define | WRAP(x) |
Functions | |
static PyObject * | _allFramesAsDot (PyObject *self, PyObject *args, PyObject *kw) |
static PyObject * | _chain (PyObject *self, PyObject *args, PyObject *kw) |
static PyObject * | _frameExists (PyObject *self, PyObject *args) |
static PyObject * | _getFrameStrings (PyObject *self, PyObject *args) |
static PyObject * | allFramesAsString (PyObject *self, PyObject *args) |
static PyObject * | allFramesAsYAML (PyObject *self, PyObject *args) |
static PyObject * | asListOfStrings (std::vector< std::string > los) |
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 int | checkRotationType (PyObject *o) |
static int | checkTranslationType (PyObject *o) |
static PyObject * | clear (PyObject *self, PyObject *args) |
static PyObject * | getLatestCommonTime (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) |
PyObject * | moduleInit (PyObject *m) |
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) |
bool | staticInit () |
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 10 of file tf2_py.cpp.
static PyObject* _allFramesAsDot | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 532 of file tf2_py.cpp.
static PyObject* _chain | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 259 of file tf2_py.cpp.
static PyObject* _frameExists | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 515 of file tf2_py.cpp.
static PyObject* _getFrameStrings | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 524 of file tf2_py.cpp.
static PyObject* allFramesAsString | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 206 of file tf2_py.cpp.
static PyObject* allFramesAsYAML | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 200 of file tf2_py.cpp.
static PyObject* asListOfStrings | ( | std::vector< std::string > | los | ) | [static] |
Definition at line 249 of file tf2_py.cpp.
static int BufferCore_init | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 176 of file tf2_py.cpp.
static PyObject* canTransformCore | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 212 of file tf2_py.cpp.
static PyObject* canTransformFullCore | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 227 of file tf2_py.cpp.
static int checkRotationType | ( | PyObject * | o | ) | [inline, static] |
Definition at line 408 of file tf2_py.cpp.
static int checkTranslationType | ( | PyObject * | o | ) | [inline, static] |
Definition at line 395 of file tf2_py.cpp.
static PyObject* clear | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 508 of file tf2_py.cpp.
static PyObject* getLatestCommonTime | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 281 of file tf2_py.cpp.
void init_tf2 | ( | ) |
Definition at line 619 of file tf2_py.cpp.
static PyObject* lookupTransformCore | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 307 of file tf2_py.cpp.
static PyObject* lookupTransformFullCore | ( | PyObject * | self, |
PyObject * | args, | ||
PyObject * | kw | ||
) | [static] |
Definition at line 327 of file tf2_py.cpp.
PyObject* moduleInit | ( | PyObject * | m | ) |
Definition at line 606 of file tf2_py.cpp.
static int rosduration_converter | ( | PyObject * | obj, |
ros::Duration * | rt | ||
) | [static] |
Definition at line 163 of file tf2_py.cpp.
static int rostime_converter | ( | PyObject * | obj, |
ros::Time * | rt | ||
) | [static] |
Definition at line 150 of file tf2_py.cpp.
static PyObject* setTransform | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 422 of file tf2_py.cpp.
static PyObject* setTransformStatic | ( | PyObject * | self, |
PyObject * | args | ||
) | [static] |
Definition at line 465 of file tf2_py.cpp.
bool staticInit | ( | ) |
Definition at line 570 of file tf2_py.cpp.
static PyObject* transform_converter | ( | const geometry_msgs::TransformStamped * | transform | ) | [static] |
Definition at line 71 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_VARARGS | METH_KEYWORDS}, {"can_transform_full_core", (PyCFunction)canTransformFullCore, METH_VARARGS | METH_KEYWORDS}, {"_chain", (PyCFunction)_chain, METH_VARARGS | METH_KEYWORDS}, {"clear", (PyCFunction)clear, METH_VARARGS | METH_KEYWORDS}, {"_frameExists", (PyCFunction)_frameExists, METH_VARARGS}, {"_getFrameStrings", (PyCFunction)_getFrameStrings, METH_VARARGS}, {"_allFramesAsDot", (PyCFunction)_allFramesAsDot, METH_VARARGS | METH_KEYWORDS}, {"get_latest_common_time", (PyCFunction)getLatestCommonTime, METH_VARARGS}, {"lookup_transform_core", (PyCFunction)lookupTransformCore, METH_VARARGS | METH_KEYWORDS}, {"lookup_transform_full_core", (PyCFunction)lookupTransformFullCore, METH_VARARGS | METH_KEYWORDS}, {NULL, NULL} }
Definition at line 543 of file tf2_py.cpp.
PyTypeObject buffer_core_Type [static] |
{ PyObject_HEAD_INIT(NULL) 0, "_tf2.BufferCore", sizeof(buffer_core_t), }
Definition at line 60 of file tf2_py.cpp.
PyMethodDef module_methods[] [static] |
{ {0, 0, 0}, }
Definition at line 565 of file tf2_py.cpp.
PyObject* pModulegeometrymsgs = NULL [static] |
Definition at line 49 of file tf2_py.cpp.
PyObject* pModulerospy = NULL [static] |
Definition at line 48 of file tf2_py.cpp.
PyObject* tf2_connectivityexception = NULL [static] |
Definition at line 51 of file tf2_py.cpp.
PyObject* tf2_exception = NULL [static] |
Definition at line 50 of file tf2_py.cpp.
PyObject * tf2_extrapolationexception = NULL [static] |
Definition at line 51 of file tf2_py.cpp.
PyObject * tf2_invalidargumentexception = NULL [static] |
Definition at line 52 of file tf2_py.cpp.
PyObject * tf2_lookupexception = NULL [static] |
Definition at line 51 of file tf2_py.cpp.
PyObject * tf2_timeoutexception = NULL [static] |
Definition at line 52 of file tf2_py.cpp.