tf2_py.cpp
Go to the documentation of this file.
1 #include <Python.h>
2 
3 #include <tf2/buffer_core.h>
4 #include <tf2/exceptions.h>
5 
6 #include "python_compat.h"
7 
8 // Run x (a tf method, catching TF's exceptions and reraising them as Python exceptions)
9 //
10 #define WRAP(x) \
11  do { \
12  try \
13  { \
14  x; \
15  } \
16  catch (const tf2::ConnectivityException &e) \
17  { \
18  PyErr_SetString(tf2_connectivityexception, e.what()); \
19  return NULL; \
20  } \
21  catch (const tf2::LookupException &e) \
22  { \
23  PyErr_SetString(tf2_lookupexception, e.what()); \
24  return NULL; \
25  } \
26  catch (const tf2::ExtrapolationException &e) \
27  { \
28  PyErr_SetString(tf2_extrapolationexception, e.what()); \
29  return NULL; \
30  } \
31  catch (const tf2::InvalidArgumentException &e) \
32  { \
33  PyErr_SetString(tf2_invalidargumentexception, e.what()); \
34  return NULL; \
35  } \
36  catch (const tf2::TimeoutException &e) \
37  { \
38  PyErr_SetString(tf2_timeoutexception, e.what()); \
39  return NULL; \
40  } \
41  catch (const tf2::TransformException &e) \
42  { \
43  PyErr_SetString(tf2_exception, e.what()); \
44  return NULL; \
45  } \
46  } while (0)
47 
48 static PyObject *pModulerospy = NULL;
49 static PyObject *pModulegeometrymsgs = NULL;
50 static PyObject *tf2_exception = NULL;
53 
54 struct buffer_core_t {
55  PyObject_HEAD
57 };
58 
59 
60 static PyTypeObject buffer_core_Type = {
61 #if PY_MAJOR_VERSION < 3
62  PyObject_HEAD_INIT(NULL)
63  0, /*size*/
64 # else
65  PyVarObject_HEAD_INIT(NULL, 0)
66 #endif
67  "_tf2.BufferCore", /*name*/
68  sizeof(buffer_core_t), /*basicsize*/
69 };
70 
71 static PyObject *transform_converter(const geometry_msgs::TransformStamped* transform)
72 {
73  PyObject *pclass, *pargs, *pinst = NULL;
74  pclass = PyObject_GetAttrString(pModulegeometrymsgs, "TransformStamped");
75  if(pclass == NULL)
76  {
77  printf("Can't get geometry_msgs.msg.TransformedStamped\n");
78  return NULL;
79  }
80 
81  pargs = Py_BuildValue("()");
82  if(pargs == NULL)
83  {
84  Py_DECREF(pclass);
85  printf("Can't build argument list\n");
86  return NULL;
87  }
88 
89  pinst = PyEval_CallObject(pclass, pargs);
90  Py_DECREF(pclass);
91  Py_DECREF(pargs);
92  if(pinst == NULL)
93  {
94  printf("Can't create class\n");
95  return NULL;
96  }
97 
98  //we need to convert the time to python
99  PyObject *rospy_time = PyObject_GetAttrString(pModulerospy, "Time");
100  PyObject *args = Py_BuildValue("ii", transform->header.stamp.sec, transform->header.stamp.nsec);
101  PyObject *time_obj = PyObject_CallObject(rospy_time, args);
102  Py_DECREF(args);
103  Py_DECREF(rospy_time);
104 
105  PyObject* pheader = PyObject_GetAttrString(pinst, "header");
106  PyObject_SetAttrString(pheader, "stamp", time_obj);
107  Py_DECREF(time_obj);
108 
109  PyObject *frame_id = stringToPython(transform->header.frame_id);
110  PyObject_SetAttrString(pheader, "frame_id", frame_id);
111  Py_DECREF(frame_id);
112  Py_DECREF(pheader);
113 
114  PyObject *ptransform = PyObject_GetAttrString(pinst, "transform");
115  PyObject *ptranslation = PyObject_GetAttrString(ptransform, "translation");
116  PyObject *protation = PyObject_GetAttrString(ptransform, "rotation");
117  Py_DECREF(ptransform);
118 
119  PyObject *child_frame_id = stringToPython(transform->child_frame_id);
120  PyObject_SetAttrString(pinst, "child_frame_id", child_frame_id);
121  Py_DECREF(child_frame_id);
122 
123  PyObject *trans_x = PyFloat_FromDouble(transform->transform.translation.x);
124  PyObject *trans_y = PyFloat_FromDouble(transform->transform.translation.y);
125  PyObject *trans_z = PyFloat_FromDouble(transform->transform.translation.z);
126  PyObject_SetAttrString(ptranslation, "x", trans_x);
127  PyObject_SetAttrString(ptranslation, "y", trans_y);
128  PyObject_SetAttrString(ptranslation, "z", trans_z);
129  Py_DECREF(trans_x);
130  Py_DECREF(trans_y);
131  Py_DECREF(trans_z);
132  Py_DECREF(ptranslation);
133 
134  PyObject *rot_x = PyFloat_FromDouble(transform->transform.rotation.x);
135  PyObject *rot_y = PyFloat_FromDouble(transform->transform.rotation.y);
136  PyObject *rot_z = PyFloat_FromDouble(transform->transform.rotation.z);
137  PyObject *rot_w = PyFloat_FromDouble(transform->transform.rotation.w);
138  PyObject_SetAttrString(protation, "x", rot_x);
139  PyObject_SetAttrString(protation, "y", rot_y);
140  PyObject_SetAttrString(protation, "z", rot_z);
141  PyObject_SetAttrString(protation, "w", rot_w);
142  Py_DECREF(rot_x);
143  Py_DECREF(rot_y);
144  Py_DECREF(rot_z);
145  Py_DECREF(rot_w);
146  Py_DECREF(protation);
147 
148  return pinst;
149 }
150 
151 static int rostime_converter(PyObject *obj, ros::Time *rt)
152 {
153  PyObject *tsr = PyObject_CallMethod(obj, (char*)"to_sec", NULL);
154  if (tsr == NULL) {
155  PyErr_SetString(PyExc_TypeError, "time must have a to_sec method, e.g. rospy.Time or rospy.Duration");
156  return 0;
157  } else {
158  (*rt).fromSec(PyFloat_AsDouble(tsr));
159  Py_DECREF(tsr);
160  return 1;
161  }
162 }
163 
164 static int rosduration_converter(PyObject *obj, ros::Duration *rt)
165 {
166  PyObject *tsr = PyObject_CallMethod(obj, (char*)"to_sec", NULL);
167  if (tsr == NULL) {
168  PyErr_SetString(PyExc_TypeError, "time must have a to_sec method, e.g. rospy.Time or rospy.Duration");
169  return 0;
170  } else {
171  (*rt).fromSec(PyFloat_AsDouble(tsr));
172  Py_DECREF(tsr);
173  return 1;
174  }
175 }
176 
177 static int BufferCore_init(PyObject *self, PyObject *args, PyObject *kw)
178 {
179  ros::Duration cache_time;
180 
182 
183  if (!PyArg_ParseTuple(args, "|O&", rosduration_converter, &cache_time))
184  return -1;
185 
186  ((buffer_core_t*)self)->bc = new tf2::BufferCore(cache_time);
187 
188  return 0;
189 }
190 
191 /* This may need to be implemented later if we decide to have it in the core
192 static PyObject *getTFPrefix(PyObject *self, PyObject *args)
193 {
194  if (!PyArg_ParseTuple(args, ""))
195  return NULL;
196  tf::Transformer *t = ((transformer_t*)self)->t;
197  return stringToPython(t->getTFPrefix());
198 }
199 */
200 
201 static PyObject *allFramesAsYAML(PyObject *self, PyObject *args)
202 {
203  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
204  return stringToPython(bc->allFramesAsYAML());
205 }
206 
207 static PyObject *allFramesAsString(PyObject *self, PyObject *args)
208 {
209  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
210  return stringToPython(bc->allFramesAsString());
211 }
212 
213 static PyObject *canTransformCore(PyObject *self, PyObject *args, PyObject *kw)
214 {
215  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
216  char *target_frame, *source_frame;
217  ros::Time time;
218  static const char *keywords[] = { "target_frame", "source_frame", "time", NULL };
219 
220  if (!PyArg_ParseTupleAndKeywords(args, kw, "ssO&", (char**)keywords, &target_frame, &source_frame, rostime_converter, &time))
221  return NULL;
222  std::string error_msg;
223  bool can_transform = bc->canTransform(target_frame, source_frame, time, &error_msg);
224  //return PyBool_FromLong(t->canTransform(target_frame, source_frame, time));
225  return Py_BuildValue("bs", can_transform, error_msg.c_str());
226 }
227 
228 static PyObject *canTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
229 {
230  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
231  char *target_frame, *source_frame, *fixed_frame;
232  ros::Time target_time, source_time;
233  static const char *keywords[] = { "target_frame", "target_time", "source_frame", "source_time", "fixed_frame", NULL };
234 
235  if (!PyArg_ParseTupleAndKeywords(args, kw, "sO&sO&s", (char**)keywords,
236  &target_frame,
238  &target_time,
239  &source_frame,
241  &source_time,
242  &fixed_frame))
243  return NULL;
244  std::string error_msg;
245  bool can_transform = bc->canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, &error_msg);
246  //return PyBool_FromLong(t->canTransform(target_frame, target_time, source_frame, source_time, fixed_frame));
247  return Py_BuildValue("bs", can_transform, error_msg.c_str());
248 }
249 
250 static PyObject *asListOfStrings(std::vector< std::string > los)
251 {
252  PyObject *r = PyList_New(los.size());
253  size_t i;
254  for (i = 0; i < los.size(); i++) {
255  PyList_SetItem(r, i, stringToPython(los[i]));
256  }
257  return r;
258 }
259 
260 static PyObject *_chain(PyObject *self, PyObject *args, PyObject *kw)
261 {
262  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
263  char *target_frame, *source_frame, *fixed_frame;
264  ros::Time target_time, source_time;
265  std::vector< std::string > output;
266  static const char *keywords[] = { "target_frame", "target_time", "source_frame", "source_time", "fixed_frame", NULL };
267 
268  if (!PyArg_ParseTupleAndKeywords(args, kw, "sO&sO&s", (char**)keywords,
269  &target_frame,
271  &target_time,
272  &source_frame,
274  &source_time,
275  &fixed_frame))
276  return NULL;
277 
278  WRAP(bc->_chainAsVector(target_frame, target_time, source_frame, source_time, fixed_frame, output));
279  return asListOfStrings(output);
280 }
281 
282 static PyObject *getLatestCommonTime(PyObject *self, PyObject *args)
283 {
284  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
285  char *target_frame, *source_frame;
286  tf2::CompactFrameID target_id, source_id;
287  ros::Time time;
288  std::string error_string;
289 
290  if (!PyArg_ParseTuple(args, "ss", &target_frame, &source_frame))
291  return NULL;
292  WRAP(target_id = bc->_validateFrameId("get_latest_common_time", target_frame));
293  WRAP(source_id = bc->_validateFrameId("get_latest_common_time", source_frame));
294  int r = bc->_getLatestCommonTime(target_id, source_id, time, &error_string);
295  if (r == 0) {
296  PyObject *rospy_time = PyObject_GetAttrString(pModulerospy, "Time");
297  PyObject *args = Py_BuildValue("ii", time.sec, time.nsec);
298  PyObject *ob = PyObject_CallObject(rospy_time, args);
299  Py_DECREF(args);
300  Py_DECREF(rospy_time);
301  return ob;
302  } else {
303  PyErr_SetString(tf2_exception, error_string.c_str());
304  return NULL;
305  }
306 }
307 
308 static PyObject *lookupTransformCore(PyObject *self, PyObject *args, PyObject *kw)
309 {
310  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
311  char *target_frame, *source_frame;
312  ros::Time time;
313  static const char *keywords[] = { "target_frame", "source_frame", "time", NULL };
314 
315  if (!PyArg_ParseTupleAndKeywords(args, kw, "ssO&", (char**)keywords, &target_frame, &source_frame, rostime_converter, &time))
316  return NULL;
317  geometry_msgs::TransformStamped transform;
318  WRAP(transform = bc->lookupTransform(target_frame, source_frame, time));
319  geometry_msgs::Vector3 origin = transform.transform.translation;
320  geometry_msgs::Quaternion rotation = transform.transform.rotation;
321  //TODO: Create a converter that will actually return a python message
322  return Py_BuildValue("O&", transform_converter, &transform);
323  //return Py_BuildValue("(ddd)(dddd)",
324  // origin.x, origin.y, origin.z,
325  // rotation.x, rotation.y, rotation.z, rotation.w);
326 }
327 
328 static PyObject *lookupTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
329 {
330  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
331  char *target_frame, *source_frame, *fixed_frame;
332  ros::Time target_time, source_time;
333  static const char *keywords[] = { "target_frame", "target_time", "source_frame", "source_time", "fixed_frame", NULL };
334 
335  if (!PyArg_ParseTupleAndKeywords(args, kw, "sO&sO&s", (char**)keywords,
336  &target_frame,
338  &target_time,
339  &source_frame,
341  &source_time,
342  &fixed_frame))
343  return NULL;
344  geometry_msgs::TransformStamped transform;
345  WRAP(transform = bc->lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame));
346  geometry_msgs::Vector3 origin = transform.transform.translation;
347  geometry_msgs::Quaternion rotation = transform.transform.rotation;
348  //TODO: Create a converter that will actually return a python message
349  return Py_BuildValue("O&", transform_converter, &transform);
350 }
351 /*
352 static PyObject *lookupTwistCore(PyObject *self, PyObject *args, PyObject *kw)
353 {
354  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
355  char *tracking_frame, *observation_frame;
356  ros::Time time;
357  ros::Duration averaging_interval;
358  static const char *keywords[] = { "tracking_frame", "observation_frame", "time", "averaging_interval", NULL };
359 
360  if (!PyArg_ParseTupleAndKeywords(args, kw, "ssO&O&", (char**)keywords, &tracking_frame, &observation_frame, rostime_converter, &time, rosduration_converter, &averaging_interval))
361  return NULL;
362  geometry_msgs::Twist twist;
363  WRAP(twist = bc->lookupTwist(tracking_frame, observation_frame, time, averaging_interval));
364 
365  return Py_BuildValue("(ddd)(ddd)",
366  twist.linear.x, twist.linear.y, twist.linear.z,
367  twist.angular.x, twist.angular.y, twist.angular.z);
368 }
369 
370 static PyObject *lookupTwistFullCore(PyObject *self, PyObject *args)
371 {
372  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
373  char *tracking_frame, *observation_frame, *reference_frame, *reference_point_frame;
374  ros::Time time;
375  ros::Duration averaging_interval;
376  double px, py, pz;
377 
378  if (!PyArg_ParseTuple(args, "sss(ddd)sO&O&",
379  &tracking_frame,
380  &observation_frame,
381  &reference_frame,
382  &px, &py, &pz,
383  &reference_point_frame,
384  rostime_converter, &time,
385  rosduration_converter, &averaging_interval))
386  return NULL;
387  geometry_msgs::Twist twist;
388  tf::Point pt(px, py, pz);
389  WRAP(twist = bc->lookupTwist(tracking_frame, observation_frame, reference_frame, pt, reference_point_frame, time, averaging_interval));
390 
391  return Py_BuildValue("(ddd)(ddd)",
392  twist.linear.x, twist.linear.y, twist.linear.z,
393  twist.angular.x, twist.angular.y, twist.angular.z);
394 }
395 */
396 static inline int checkTranslationType(PyObject* o)
397 {
398  PyTypeObject *translation_type = (PyTypeObject*) PyObject_GetAttrString(pModulegeometrymsgs, "Vector3");
399  int type_check = PyObject_TypeCheck(o, translation_type);
400  int attr_check = PyObject_HasAttrString(o, "x") &&
401  PyObject_HasAttrString(o, "y") &&
402  PyObject_HasAttrString(o, "z");
403  if (!type_check) {
404  PyErr_WarnEx(PyExc_UserWarning, "translation should be of type Vector3", 1);
405  }
406  return attr_check;
407 }
408 
409 static inline int checkRotationType(PyObject* o)
410 {
411  PyTypeObject *rotation_type = (PyTypeObject*) PyObject_GetAttrString(pModulegeometrymsgs, "Quaternion");
412  int type_check = PyObject_TypeCheck(o, rotation_type);
413  int attr_check = PyObject_HasAttrString(o, "w") &&
414  PyObject_HasAttrString(o, "x") &&
415  PyObject_HasAttrString(o, "y") &&
416  PyObject_HasAttrString(o, "z");
417  if (!type_check) {
418  PyErr_WarnEx(PyExc_UserWarning, "rotation should be of type Quaternion", 1);
419  }
420  return attr_check;
421 }
422 
423 static PyObject *setTransform(PyObject *self, PyObject *args)
424 {
425  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
426  PyObject *py_transform;
427  char *authority;
428 
429  if (!PyArg_ParseTuple(args, "Os", &py_transform, &authority))
430  return NULL;
431 
432  geometry_msgs::TransformStamped transform;
433  PyObject *header = pythonBorrowAttrString(py_transform, "header");
434  transform.child_frame_id = stringFromPython(pythonBorrowAttrString(py_transform, "child_frame_id"));
435  transform.header.frame_id = stringFromPython(pythonBorrowAttrString(header, "frame_id"));
436  if (rostime_converter(pythonBorrowAttrString(header, "stamp"), &transform.header.stamp) != 1)
437  return NULL;
438 
439  PyObject *mtransform = pythonBorrowAttrString(py_transform, "transform");
440 
441  PyObject *translation = pythonBorrowAttrString(mtransform, "translation");
442  if (!checkTranslationType(translation)) {
443  PyErr_SetString(PyExc_TypeError, "transform.translation must have members x, y, z");
444  return NULL;
445  }
446 
447  transform.transform.translation.x = PyFloat_AsDouble(pythonBorrowAttrString(translation, "x"));
448  transform.transform.translation.y = PyFloat_AsDouble(pythonBorrowAttrString(translation, "y"));
449  transform.transform.translation.z = PyFloat_AsDouble(pythonBorrowAttrString(translation, "z"));
450 
451  PyObject *rotation = pythonBorrowAttrString(mtransform, "rotation");
452  if (!checkRotationType(rotation)) {
453  PyErr_SetString(PyExc_TypeError, "transform.rotation must have members w, x, y, z");
454  return NULL;
455  }
456 
457  transform.transform.rotation.x = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "x"));
458  transform.transform.rotation.y = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "y"));
459  transform.transform.rotation.z = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "z"));
460  transform.transform.rotation.w = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "w"));
461 
462  bc->setTransform(transform, authority);
463  Py_RETURN_NONE;
464 }
465 
466 static PyObject *setTransformStatic(PyObject *self, PyObject *args)
467 {
468  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
469  PyObject *py_transform;
470  char *authority;
471 
472  if (!PyArg_ParseTuple(args, "Os", &py_transform, &authority))
473  return NULL;
474 
475  geometry_msgs::TransformStamped transform;
476  PyObject *header = pythonBorrowAttrString(py_transform, "header");
477  transform.child_frame_id = stringFromPython(pythonBorrowAttrString(py_transform, "child_frame_id"));
478  transform.header.frame_id = stringFromPython(pythonBorrowAttrString(header, "frame_id"));
479  if (rostime_converter(pythonBorrowAttrString(header, "stamp"), &transform.header.stamp) != 1)
480  return NULL;
481 
482  PyObject *mtransform = pythonBorrowAttrString(py_transform, "transform");
483  PyObject *translation = pythonBorrowAttrString(mtransform, "translation");
484  if (!checkTranslationType(translation)) {
485  PyErr_SetString(PyExc_TypeError, "transform.translation must be of type Vector3");
486  return NULL;
487  }
488 
489  transform.transform.translation.x = PyFloat_AsDouble(pythonBorrowAttrString(translation, "x"));
490  transform.transform.translation.y = PyFloat_AsDouble(pythonBorrowAttrString(translation, "y"));
491  transform.transform.translation.z = PyFloat_AsDouble(pythonBorrowAttrString(translation, "z"));
492 
493  PyObject *rotation = pythonBorrowAttrString(mtransform, "rotation");
494  if (!checkRotationType(rotation)) {
495  PyErr_SetString(PyExc_TypeError, "transform.rotation must be of type Quaternion");
496  return NULL;
497  }
498 
499  transform.transform.rotation.x = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "x"));
500  transform.transform.rotation.y = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "y"));
501  transform.transform.rotation.z = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "z"));
502  transform.transform.rotation.w = PyFloat_AsDouble(pythonBorrowAttrString(rotation, "w"));
503 
504  // only difference to above is is_static == True
505  bc->setTransform(transform, authority, true);
506  Py_RETURN_NONE;
507 }
508 
509 static PyObject *clear(PyObject *self, PyObject *args)
510 {
511  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
512  bc->clear();
513  Py_RETURN_NONE;
514 }
515 
516 static PyObject *_frameExists(PyObject *self, PyObject *args)
517 {
518  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
519  char *frame_id_str;
520  if (!PyArg_ParseTuple(args, "s", &frame_id_str))
521  return NULL;
522  return PyBool_FromLong(bc->_frameExists(frame_id_str));
523 }
524 
525 static PyObject *_getFrameStrings(PyObject *self, PyObject *args)
526 {
527  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
528  std::vector< std::string > ids;
529  bc->_getFrameStrings(ids);
530  return asListOfStrings(ids);
531 }
532 
533 static PyObject *_allFramesAsDot(PyObject *self, PyObject *args, PyObject *kw)
534 {
535  tf2::BufferCore *bc = ((buffer_core_t*)self)->bc;
536  static const char *keywords[] = { "time", NULL };
537  ros::Time time;
538  if (!PyArg_ParseTupleAndKeywords(args, kw, "|O&", (char**)keywords, rostime_converter, &time))
539  return NULL;
540  return stringToPython(bc->_allFramesAsDot(time.toSec()));
541 }
542 
543 
544 static struct PyMethodDef buffer_core_methods[] =
545 {
546  {"all_frames_as_yaml", allFramesAsYAML, METH_VARARGS},
547  {"all_frames_as_string", allFramesAsString, METH_VARARGS},
548  {"set_transform", setTransform, METH_VARARGS},
549  {"set_transform_static", setTransformStatic, METH_VARARGS},
550  {"can_transform_core", (PyCFunction)canTransformCore, METH_VARARGS | METH_KEYWORDS},
551  {"can_transform_full_core", (PyCFunction)canTransformFullCore, METH_VARARGS | METH_KEYWORDS},
552  {"_chain", (PyCFunction)_chain, METH_VARARGS | METH_KEYWORDS},
553  {"clear", (PyCFunction)clear, METH_VARARGS | METH_KEYWORDS},
554  {"_frameExists", (PyCFunction)_frameExists, METH_VARARGS},
555  {"_getFrameStrings", (PyCFunction)_getFrameStrings, METH_VARARGS},
556  {"_allFramesAsDot", (PyCFunction)_allFramesAsDot, METH_VARARGS | METH_KEYWORDS},
557  {"get_latest_common_time", (PyCFunction)getLatestCommonTime, METH_VARARGS},
558  {"lookup_transform_core", (PyCFunction)lookupTransformCore, METH_VARARGS | METH_KEYWORDS},
559  {"lookup_transform_full_core", (PyCFunction)lookupTransformFullCore, METH_VARARGS | METH_KEYWORDS},
560  //{"lookupTwistCore", (PyCFunction)lookupTwistCore, METH_VARARGS | METH_KEYWORDS},
561  //{"lookupTwistFullCore", lookupTwistFullCore, METH_VARARGS},
562  //{"getTFPrefix", (PyCFunction)getTFPrefix, METH_VARARGS},
563  {NULL, NULL}
564 };
565 
566 static PyMethodDef module_methods[] = {
567  // {"Transformer", mkTransformer, METH_VARARGS},
568  {0, 0, 0},
569 };
570 
571 bool staticInit() {
572 #if PYTHON_API_VERSION >= 1007
573  tf2_exception = PyErr_NewException((char*)"tf2.TransformException", NULL, NULL);
574  tf2_connectivityexception = PyErr_NewException((char*)"tf2.ConnectivityException", tf2_exception, NULL);
575  tf2_lookupexception = PyErr_NewException((char*)"tf2.LookupException", tf2_exception, NULL);
576  tf2_extrapolationexception = PyErr_NewException((char*)"tf2.ExtrapolationException", tf2_exception, NULL);
577  tf2_invalidargumentexception = PyErr_NewException((char*)"tf2.InvalidArgumentException", tf2_exception, NULL);
578  tf2_timeoutexception = PyErr_NewException((char*)"tf2.TimeoutException", tf2_exception, NULL);
579 #else
580  tf2_exception = stringToPython("tf2.error");
581  tf2_connectivityexception = stringToPython("tf2.ConnectivityException");
582  tf2_lookupexception = stringToPython("tf2.LookupException");
583  tf2_extrapolationexception = stringToPython("tf2.ExtrapolationException");
584  tf2_invalidargumentexception = stringToPython("tf2.InvalidArgumentException");
585  tf2_timeoutexception = stringToPython("tf2.TimeoutException");
586 #endif
587 
588  pModulerospy = pythonImport("rospy");
589  pModulegeometrymsgs = pythonImport("geometry_msgs.msg");
590 
591  if(pModulegeometrymsgs == NULL)
592  {
593  printf("Cannot load geometry_msgs module");
594  return false;
595  }
596 
597  buffer_core_Type.tp_alloc = PyType_GenericAlloc;
598  buffer_core_Type.tp_new = PyType_GenericNew;
600  buffer_core_Type.tp_flags = Py_TPFLAGS_DEFAULT | Py_TPFLAGS_BASETYPE;
602  if (PyType_Ready(&buffer_core_Type) != 0)
603  return false;
604  return true;
605 }
606 
607 PyObject *moduleInit(PyObject *m) {
608  PyModule_AddObject(m, "BufferCore", (PyObject *)&buffer_core_Type);
609  PyObject *d = PyModule_GetDict(m);
610  PyDict_SetItemString(d, "TransformException", tf2_exception);
611  PyDict_SetItemString(d, "ConnectivityException", tf2_connectivityexception);
612  PyDict_SetItemString(d, "LookupException", tf2_lookupexception);
613  PyDict_SetItemString(d, "ExtrapolationException", tf2_extrapolationexception);
614  PyDict_SetItemString(d, "InvalidArgumentException", tf2_invalidargumentexception);
615  PyDict_SetItemString(d, "TimeoutException", tf2_timeoutexception);
616  return m;
617 }
618 
619 #if PY_MAJOR_VERSION < 3
620 extern "C"
621 {
623  {
624  if (!staticInit())
625  return;
626  moduleInit(Py_InitModule("_tf2", module_methods));
627  }
628 }
629 
630 #else
631 struct PyModuleDef tf_module = {
632  PyModuleDef_HEAD_INIT, // base
633  "_tf2", // name
634  NULL, // docstring
635  -1, // state size (but we're using globals)
636  module_methods // methods
637 };
638 
639 PyMODINIT_FUNC PyInit__tf2()
640 {
641  if (!staticInit())
642  return NULL;
643  return moduleInit(PyModule_Create(&tf_module));
644 }
645 #endif
buffer_core_t::bc
PyObject_HEAD tf2::BufferCore * bc
Definition: tf2_py.cpp:56
canTransformFullCore
static PyObject * canTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:228
transform_converter
static PyObject * transform_converter(const geometry_msgs::TransformStamped *transform)
Definition: tf2_py.cpp:71
DurationBase< Duration >::fromSec
Duration & fromSec(double t)
buffer_core_Type
static PyTypeObject buffer_core_Type
Definition: tf2_py.cpp:60
tf2_timeoutexception
static PyObject * tf2_timeoutexception
Definition: tf2_py.cpp:52
tf2::BufferCore::_validateFrameId
CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
staticInit
bool staticInit()
Definition: tf2_py.cpp:571
_frameExists
static PyObject * _frameExists(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:516
allFramesAsYAML
static PyObject * allFramesAsYAML(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:201
tf2::BufferCore::setTransform
bool setTransform(const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
tf2::BufferCore::lookupTransform
geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame) const
_getFrameStrings
static PyObject * _getFrameStrings(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:525
TimeBase< Time, Duration >::toSec
double toSec() const
tf2::BufferCore::allFramesAsYAML
std::string allFramesAsYAML() const
python_compat.h
setTransform
static PyObject * setTransform(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:423
pythonBorrowAttrString
PyObject * pythonBorrowAttrString(PyObject *o, const char *name)
Definition: python_compat.h:47
tf2_extrapolationexception
static PyObject * tf2_extrapolationexception
Definition: tf2_py.cpp:51
tf2_connectivityexception
static PyObject * tf2_connectivityexception
Definition: tf2_py.cpp:51
lookupTransformFullCore
static PyObject * lookupTransformFullCore(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:328
tf2::BufferCore::_getLatestCommonTime
int _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
_allFramesAsDot
static PyObject * _allFramesAsDot(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:533
checkTranslationType
static int checkTranslationType(PyObject *o)
Definition: tf2_py.cpp:396
allFramesAsString
static PyObject * allFramesAsString(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:207
tf2::CompactFrameID
uint32_t CompactFrameID
pModulerospy
static PyObject * pModulerospy
Definition: tf2_py.cpp:48
stringToPython
PyObject * stringToPython(const std::string &input)
Definition: python_compat.h:8
clear
static PyObject * clear(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:509
tf2::BufferCore::allFramesAsString
std::string allFramesAsString() const
tf2::BufferCore::_chainAsVector
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
tf2::BufferCore::_getFrameStrings
void _getFrameStrings(std::vector< std::string > &ids) const
rosduration_converter
static int rosduration_converter(PyObject *obj, ros::Duration *rt)
Definition: tf2_py.cpp:164
tf2_exception
static PyObject * tf2_exception
Definition: tf2_py.cpp:50
canTransformCore
static PyObject * canTransformCore(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:213
_chain
static PyObject * _chain(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:260
pModulegeometrymsgs
static PyObject * pModulegeometrymsgs
Definition: tf2_py.cpp:49
setTransformStatic
static PyObject * setTransformStatic(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:466
asListOfStrings
static PyObject * asListOfStrings(std::vector< std::string > los)
Definition: tf2_py.cpp:250
buffer_core_methods
static struct PyMethodDef buffer_core_methods[]
Definition: tf2_py.cpp:544
tf2::BufferCore::clear
void clear()
getLatestCommonTime
static PyObject * getLatestCommonTime(PyObject *self, PyObject *args)
Definition: tf2_py.cpp:282
tf2_lookupexception
static PyObject * tf2_lookupexception
Definition: tf2_py.cpp:51
tf2::BufferCore::_allFramesAsDot
std::string _allFramesAsDot() const
setup.d
d
Definition: setup.py:6
tf2::BufferCore::canTransform
bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
tf2::BufferCore::_frameExists
bool _frameExists(const std::string &frame_id_str) const
buffer_core.h
TimeBase< Time, Duration >::sec
uint32_t sec
TimeBase< Time, Duration >::nsec
uint32_t nsec
exceptions.h
init_tf2
ROS_HELPER_EXPORT void init_tf2()
Definition: tf2_py.cpp:622
ros::Time
tf2::BufferCore
lookupTransformCore
static PyObject * lookupTransformCore(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:308
tf2::BufferCore::DEFAULT_CACHE_TIME
static const int DEFAULT_CACHE_TIME
checkRotationType
static int checkRotationType(PyObject *o)
Definition: tf2_py.cpp:409
BufferCore_init
static int BufferCore_init(PyObject *self, PyObject *args, PyObject *kw)
Definition: tf2_py.cpp:177
pythonImport
PyObject * pythonImport(const std::string &name)
Definition: python_compat.h:39
tf2_invalidargumentexception
static PyObject * tf2_invalidargumentexception
Definition: tf2_py.cpp:52
ROS_HELPER_EXPORT
#define ROS_HELPER_EXPORT
buffer_core_t
Definition: tf2_py.cpp:54
module_methods
static PyMethodDef module_methods[]
Definition: tf2_py.cpp:566
header
const std::string header
rostime_converter
static int rostime_converter(PyObject *obj, ros::Time *rt)
Definition: tf2_py.cpp:151
ros::Duration
WRAP
#define WRAP(x)
Definition: tf2_py.cpp:10
moduleInit
PyObject * moduleInit(PyObject *m)
Definition: tf2_py.cpp:607
stringFromPython
std::string stringFromPython(PyObject *input)
Definition: python_compat.h:26


tf2_py
Author(s):
autogenerated on Sun Feb 4 2024 03:18:15