16 catch (const tf2::ConnectivityException &e) \ 18 PyErr_SetString(tf2_connectivityexception, e.what()); \ 21 catch (const tf2::LookupException &e) \ 23 PyErr_SetString(tf2_lookupexception, e.what()); \ 26 catch (const tf2::ExtrapolationException &e) \ 28 PyErr_SetString(tf2_extrapolationexception, e.what()); \ 31 catch (const tf2::InvalidArgumentException &e) \ 33 PyErr_SetString(tf2_invalidargumentexception, e.what()); \ 36 catch (const tf2::TimeoutException &e) \ 38 PyErr_SetString(tf2_timeoutexception, e.what()); \ 41 catch (const tf2::TransformException &e) \ 43 PyErr_SetString(tf2_exception, e.what()); \ 61 #if PY_MAJOR_VERSION < 3 62 PyObject_HEAD_INIT(NULL)
65 PyVarObject_HEAD_INIT(NULL, 0)
73 PyObject *pclass, *pargs, *pinst = NULL;
77 printf(
"Can't get geometry_msgs.msg.TransformedStamped\n");
81 pargs = Py_BuildValue(
"()");
84 printf(
"Can't build argument list\n");
88 pinst = PyEval_CallObject(pclass, pargs);
93 printf(
"Can't create class\n");
98 PyObject *rospy_time = PyObject_GetAttrString(
pModulerospy,
"Time");
99 PyObject *args = Py_BuildValue(
"ii", transform->header.stamp.sec, transform->header.stamp.nsec);
100 PyObject *time_obj = PyObject_CallObject(rospy_time, args);
102 Py_DECREF(rospy_time);
104 PyObject* pheader = PyObject_GetAttrString(pinst,
"header");
105 PyObject_SetAttrString(pheader,
"stamp", time_obj);
109 PyObject_SetAttrString(pheader,
"frame_id", frame_id);
113 PyObject *ptransform = PyObject_GetAttrString(pinst,
"transform");
114 PyObject *ptranslation = PyObject_GetAttrString(ptransform,
"translation");
115 PyObject *protation = PyObject_GetAttrString(ptransform,
"rotation");
116 Py_DECREF(ptransform);
118 PyObject *child_frame_id =
stringToPython(transform->child_frame_id);
119 PyObject_SetAttrString(pinst,
"child_frame_id", child_frame_id);
120 Py_DECREF(child_frame_id);
122 PyObject *trans_x = PyFloat_FromDouble(transform->transform.translation.x);
123 PyObject *trans_y = PyFloat_FromDouble(transform->transform.translation.y);
124 PyObject *trans_z = PyFloat_FromDouble(transform->transform.translation.z);
125 PyObject_SetAttrString(ptranslation,
"x", trans_x);
126 PyObject_SetAttrString(ptranslation,
"y", trans_y);
127 PyObject_SetAttrString(ptranslation,
"z", trans_z);
131 Py_DECREF(ptranslation);
133 PyObject *rot_x = PyFloat_FromDouble(transform->transform.rotation.x);
134 PyObject *rot_y = PyFloat_FromDouble(transform->transform.rotation.y);
135 PyObject *rot_z = PyFloat_FromDouble(transform->transform.rotation.z);
136 PyObject *rot_w = PyFloat_FromDouble(transform->transform.rotation.w);
137 PyObject_SetAttrString(protation,
"x", rot_x);
138 PyObject_SetAttrString(protation,
"y", rot_y);
139 PyObject_SetAttrString(protation,
"z", rot_z);
140 PyObject_SetAttrString(protation,
"w", rot_w);
145 Py_DECREF(protation);
152 PyObject *tsr = PyObject_CallMethod(obj, (
char*)
"to_sec", NULL);
154 PyErr_SetString(PyExc_TypeError,
"time must have a to_sec method, e.g. rospy.Time or rospy.Duration");
157 (*rt).fromSec(PyFloat_AsDouble(tsr));
165 PyObject *tsr = PyObject_CallMethod(obj, (
char*)
"to_sec", NULL);
167 PyErr_SetString(PyExc_TypeError,
"time must have a to_sec method, e.g. rospy.Time or rospy.Duration");
170 (*rt).fromSec(PyFloat_AsDouble(tsr));
215 char *target_frame, *source_frame;
217 static const char *keywords[] = {
"target_frame",
"source_frame",
"time", NULL };
219 if (!PyArg_ParseTupleAndKeywords(args, kw,
"ssO&", (
char**)keywords, &target_frame, &source_frame,
rostime_converter, &time))
221 std::string error_msg;
222 bool can_transform = bc->
canTransform(target_frame, source_frame, time, &error_msg);
224 return Py_BuildValue(
"bs", can_transform, error_msg.c_str());
230 char *target_frame, *source_frame, *fixed_frame;
232 static const char *keywords[] = {
"target_frame",
"target_time",
"source_frame",
"source_time",
"fixed_frame", NULL };
234 if (!PyArg_ParseTupleAndKeywords(args, kw,
"sO&sO&s", (
char**)keywords,
243 std::string error_msg;
244 bool can_transform = bc->
canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, &error_msg);
246 return Py_BuildValue(
"bs", can_transform, error_msg.c_str());
251 PyObject *r = PyList_New(los.size());
253 for (i = 0; i < los.size(); i++) {
259 static PyObject *
_chain(PyObject *
self, PyObject *args, PyObject *kw)
262 char *target_frame, *source_frame, *fixed_frame;
264 std::vector< std::string > output;
265 static const char *keywords[] = {
"target_frame",
"target_time",
"source_frame",
"source_time",
"fixed_frame", NULL };
267 if (!PyArg_ParseTupleAndKeywords(args, kw,
"sO&sO&s", (
char**)keywords,
277 WRAP(bc->
_chainAsVector(target_frame, target_time, source_frame, source_time, fixed_frame, output));
284 char *target_frame, *source_frame;
287 std::string error_string;
289 if (!PyArg_ParseTuple(args,
"ss", &target_frame, &source_frame))
295 PyObject *rospy_time = PyObject_GetAttrString(
pModulerospy,
"Time");
296 PyObject *args = Py_BuildValue(
"ii", time.
sec, time.
nsec);
297 PyObject *ob = PyObject_CallObject(rospy_time, args);
299 Py_DECREF(rospy_time);
310 char *target_frame, *source_frame;
312 static const char *keywords[] = {
"target_frame",
"source_frame",
"time", NULL };
314 if (!PyArg_ParseTupleAndKeywords(args, kw,
"ssO&", (
char**)keywords, &target_frame, &source_frame,
rostime_converter, &time))
316 geometry_msgs::TransformStamped transform;
318 geometry_msgs::Vector3 origin = transform.transform.translation;
319 geometry_msgs::Quaternion rotation = transform.transform.rotation;
330 char *target_frame, *source_frame, *fixed_frame;
332 static const char *keywords[] = {
"target_frame",
"target_time",
"source_frame",
"source_time",
"fixed_frame", NULL };
334 if (!PyArg_ParseTupleAndKeywords(args, kw,
"sO&sO&s", (
char**)keywords,
343 geometry_msgs::TransformStamped transform;
344 WRAP(transform = bc->
lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame));
345 geometry_msgs::Vector3 origin = transform.transform.translation;
346 geometry_msgs::Quaternion rotation = transform.transform.rotation;
397 PyTypeObject *translation_type = (PyTypeObject*) PyObject_GetAttrString(
pModulegeometrymsgs,
"Vector3");
398 int type_check = PyObject_TypeCheck(o, translation_type);
399 int attr_check = PyObject_HasAttrString(o,
"x") &&
400 PyObject_HasAttrString(o,
"y") &&
401 PyObject_HasAttrString(o,
"z");
403 PyErr_WarnEx(PyExc_UserWarning,
"translation should be of type Vector3", 1);
410 PyTypeObject *rotation_type = (PyTypeObject*) PyObject_GetAttrString(
pModulegeometrymsgs,
"Quaternion");
411 int type_check = PyObject_TypeCheck(o, rotation_type);
412 int attr_check = PyObject_HasAttrString(o,
"w") &&
413 PyObject_HasAttrString(o,
"x") &&
414 PyObject_HasAttrString(o,
"y") &&
415 PyObject_HasAttrString(o,
"z");
417 PyErr_WarnEx(PyExc_UserWarning,
"rotation should be of type Quaternion", 1);
425 PyObject *py_transform;
428 if (!PyArg_ParseTuple(args,
"Os", &py_transform, &authority))
431 geometry_msgs::TransformStamped transform;
442 PyErr_SetString(PyExc_TypeError,
"transform.translation must have members x, y, z");
452 PyErr_SetString(PyExc_TypeError,
"transform.rotation must have members w, x, y, z");
468 PyObject *py_transform;
471 if (!PyArg_ParseTuple(args,
"Os", &py_transform, &authority))
474 geometry_msgs::TransformStamped transform;
484 PyErr_SetString(PyExc_TypeError,
"transform.translation must be of type Vector3");
494 PyErr_SetString(PyExc_TypeError,
"transform.rotation must be of type Quaternion");
508 static PyObject *
clear(PyObject *
self, PyObject *args)
519 if (!PyArg_ParseTuple(args,
"s", &frame_id_str))
527 std::vector< std::string > ids;
535 static const char *keywords[] = {
"time", NULL };
537 if (!PyArg_ParseTupleAndKeywords(args, kw,
"|O&", (
char**)keywords,
rostime_converter, &time))
549 {
"can_transform_core", (PyCFunction)
canTransformCore, METH_VARARGS | METH_KEYWORDS},
551 {
"_chain", (PyCFunction)
_chain, METH_VARARGS | METH_KEYWORDS},
552 {
"clear", (PyCFunction)
clear, METH_VARARGS | METH_KEYWORDS},
553 {
"_frameExists", (PyCFunction)
_frameExists, METH_VARARGS},
555 {
"_allFramesAsDot", (PyCFunction)
_allFramesAsDot, METH_VARARGS | METH_KEYWORDS},
571 #if PYTHON_API_VERSION >= 1007 572 tf2_exception = PyErr_NewException((
char*)
"tf2.TransformException", NULL, NULL);
592 printf(
"Cannot load geometry_msgs module");
608 PyObject *
d = PyModule_GetDict(m);
609 PyDict_SetItemString(d,
"TransformException",
tf2_exception);
618 #if PY_MAJOR_VERSION < 3 630 struct PyModuleDef tf_module = {
631 PyModuleDef_HEAD_INIT,
638 PyMODINIT_FUNC PyInit__tf2()
642 return moduleInit(PyModule_Create(&tf_module));
PyObject * stringToPython(const std::string &input)
static PyObject * _chain(PyObject *self, PyObject *args, PyObject *kw)
static int checkTranslationType(PyObject *o)
static PyMethodDef module_methods[]
static PyObject * transform_converter(const geometry_msgs::TransformStamped *transform)
CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
PyObject * pythonBorrowAttrString(PyObject *o, const char *name)
static PyObject * canTransformCore(PyObject *self, PyObject *args, PyObject *kw)
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
PyObject * moduleInit(PyObject *m)
static PyObject * _allFramesAsDot(PyObject *self, PyObject *args, PyObject *kw)
PyObject * pythonImport(const std::string &name)
static PyObject * pModulerospy
static PyObject * tf2_connectivityexception
static PyObject * _getFrameStrings(PyObject *self, PyObject *args)
std::string allFramesAsYAML(double current_time) const
static PyObject * clear(PyObject *self, PyObject *args)
std::string allFramesAsString() const
void _getFrameStrings(std::vector< std::string > &ids) const
static int rostime_converter(PyObject *obj, ros::Time *rt)
bool _frameExists(const std::string &frame_id_str) const
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
static int checkRotationType(PyObject *o)
static PyTypeObject buffer_core_Type
static struct PyMethodDef buffer_core_methods[]
static PyObject * setTransformStatic(PyObject *self, PyObject *args)
std::string _allFramesAsDot(double current_time) const
int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
#define ROS_HELPER_EXPORT
Duration & fromSec(double t)
void _chainAsVector(const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
static PyObject * tf2_exception
static PyObject * tf2_timeoutexception
static PyObject * allFramesAsYAML(PyObject *self, PyObject *args)
PyObject_HEAD tf2::BufferCore * bc
static int BufferCore_init(PyObject *self, PyObject *args, PyObject *kw)
static const int DEFAULT_CACHE_TIME
static PyObject * tf2_invalidargumentexception
static PyObject * asListOfStrings(std::vector< std::string > los)
static PyObject * canTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
static PyObject * lookupTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
static PyObject * tf2_lookupexception
static PyObject * _frameExists(PyObject *self, PyObject *args)
static PyObject * lookupTransformCore(PyObject *self, PyObject *args, PyObject *kw)
ROS_HELPER_EXPORT void init_tf2()
static PyObject * tf2_extrapolationexception
static PyObject * getLatestCommonTime(PyObject *self, PyObject *args)
static PyObject * setTransform(PyObject *self, PyObject *args)
std::string stringFromPython(PyObject *input)
static PyObject * pModulegeometrymsgs
static int rosduration_converter(PyObject *obj, ros::Duration *rt)
static PyObject * allFramesAsString(PyObject *self, PyObject *args)