eustf.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, JSK Lab, the Univ. of Tokyo
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 // author: Ryohei Ueda
36 #include <stdio.h>
37 #include <stdlib.h>
38 #include <unistd.h>
39 #include <string.h>
40 #include <signal.h>
41 #include <math.h>
42 #include <time.h>
43 #include <pthread.h>
44 #include <setjmp.h>
45 #include <errno.h>
46 
47 #include <list>
48 #include <vector>
49 #include <set>
50 #include <string>
51 #include <map>
52 #include <sstream>
53 
54 #include <cstdio>
55 #include <boost/thread/mutex.hpp>
56 #include <boost/thread/condition.hpp>
57 #include <boost/shared_ptr.hpp>
58 
59 #include <ros/init.h>
60 #include <ros/time.h>
61 #include <ros/rate.h>
62 #include <ros/master.h>
63 #include <ros/this_node.h>
64 #include <ros/node_handle.h>
65 #include <ros/service.h>
66 #include <tf/tf.h>
67 #include <tf/transform_listener.h>
68 #include <tf/transform_datatypes.h>
70 
71 #include <tf2_ros/buffer_client.h>
72 #ifdef TF2_ROS_VERSION_3 // if this is groovy
73 #define tf2_ros tf2
74 #endif
75 
76 // for eus.h
77 #define class eus_class
78 #define throw eus_throw
79 #define export eus_export
80 #define vector eus_vector
81 #define string eus_string
82 #ifdef __clang__
83 #undef MAX
84 #undef MIN
85 #endif
86 #include "eus.h"
87 
88 extern "C" {
89  pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env);
91  char modname[] = "___eustf";
92  return add_module_initializer(modname, (pointer (*)())___eustf);}
93 }
94 
95 #undef class
96 #undef throw
97 #undef export
98 #undef vector
99 #undef string
100 
101 using namespace ros;
102 using namespace std;
103 
104 
105 /***********************************************************
106  * TF wrapper
107  ************************************************************/
108 
109 #define set_ros_time(time,argv) \
110  if (isvector(argv) && (elmtypeof(argv)==ELM_INT)) { \
111  time.sec = argv->c.ivec.iv[0]; \
112  time.nsec = argv->c.ivec.iv[1]; \
113  } else { \
114  error(E_NOVECTOR); \
115  }
116 
117 /* */
119 {
120  numunion nu;
121  ckarg(2);
122  bool interpolating = ((argv[0]==T)?true:false);
123  float cache_time = ckfltval(argv[1]);
124  return(makeint((eusinteger_t)(new tf::Transformer(interpolating, ros::Duration(cache_time)))));
125 }
126 
128 {
129  ckarg(1);
130  tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
131  string str = tf->allFramesAsString();
132  return(makestring((char *)(str.c_str()), str.length()));
133 }
134 
136 {
137  ckarg(7);
138  tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
139  if (!isvector(argv[1])) error(E_NOVECTOR);
140  if (!isvector(argv[2])) error(E_NOVECTOR);
141  eusfloat_t *pos = argv[1]->c.fvec.fv;
142  eusfloat_t *rot = argv[2]->c.fvec.fv;
143  isintvector(argv[3]);
144  eusinteger_t *stamp = argv[3]->c.ivec.iv;
145  if (!isstring(argv[4])) error(E_NOSTRING);
146  if (!isstring(argv[5])) error(E_NOSTRING);
147  if (!isstring(argv[6])) error(E_NOSTRING);
148  std::string frame_id = std::string((char*)(argv[4]->c.str.chars));
149  std::string child_frame_id = std::string((char*)(argv[5]->c.str.chars));
150  std::string authority= std::string((char*)(argv[6]->c.str.chars));
151  tf::StampedTransform transform;
152  // pos (euslisp) -> [mm]
153  // pos (tf) -> [m]
154  transform.setOrigin(tf::Vector3(pos[0]/1000.0, pos[1]/1000.0, pos[2]/1000.0));
155  // rot (euslisp) -> (w, x, y, z)
156  // tfQuaternion -> (x, y, z, w)
157  transform.setRotation(tf::Quaternion(rot[1], rot[2], rot[3], rot[0]));
158  transform.frame_id_ = frame_id;
159  transform.child_frame_id_ = child_frame_id;
160  transform.stamp_.sec = stamp[0];
161  transform.stamp_.nsec = stamp[1];
162  bool ret = tf->setTransform(transform, authority);
163  return(ret?T:NIL);
164 }
165 
167 {
168  numunion nu;
169  ckarg(6);
171  std::string target_frame, source_frame;
172  ros::Time time;
173  float timeout = 0, duration = 0;
174  bool ret;
175 
176  tf = (tf::Transformer *)(intval(argv[0]));
177  if (isstring(argv[1]))
178  target_frame = std::string((char*)(argv[1]->c.str.chars));
179  else error(E_NOSTRING);
180 
181  if (isstring(argv[2]))
182  source_frame = std::string((char*)(argv[2]->c.str.chars));
183  else error(E_NOSTRING);
184 
185  set_ros_time(time,argv[3]);
186 
187  if (isint(argv[4])) timeout = (float)intval(argv[4]);
188  else if (isflt(argv[4])) timeout = (float)fltval(argv[4]);
189  else error(E_NONUMBER);
190 
191  if (isint(argv[5])) duration = (float)intval(argv[5]);
192  else if (isflt(argv[5])) duration = (float)fltval(argv[5]);
193  else error(E_NONUMBER);
194 
195  std::string err_str = std::string();
196  ret = tf->waitForTransform(target_frame, source_frame, time,
197  ros::Duration(timeout), ros::Duration(duration),
198  &err_str);
199  if(!ret) {
200  ROS_WARN_STREAM("waitForTransform failed! : " << err_str);
201  }
202  ROS_DEBUG_STREAM("waitForTransform : "
203  << "target_frame : " << target_frame
204  << "source_frame : " << source_frame
205  << "time : " << time
206  << "timeout : " << timeout
207  << "duration : " << duration
208  << "return : " << ret);
209 
210  return((ret==true)?(T):(NIL));
211 }
212 
214 {
215  numunion nu;
216  ckarg(8);
218  std::string target_frame, source_frame, fixed_frame;
219  ros::Time target_time, source_time;
220  float timeout = 0, duration = 0;
221  bool ret;
222 
223  tf = (tf::Transformer *)(intval(argv[0]));
224  if (isstring(argv[1]))
225  target_frame = std::string((char*)(argv[1]->c.str.chars));
226  else error(E_NOSTRING);
227 
228  set_ros_time(target_time,argv[2]);
229 
230  if (isstring(argv[3]))
231  source_frame = std::string((char*)(argv[3]->c.str.chars));
232  else error(E_NOSTRING);
233 
234  set_ros_time(source_time,argv[4]);
235 
236  if (isstring(argv[5]))
237  fixed_frame = std::string((char*)(argv[5]->c.str.chars));
238  else error(E_NOSTRING);
239 
240  if (isint(argv[6])) timeout = (float)intval(argv[6]);
241  else if (isflt(argv[6])) timeout = (float)fltval(argv[6]);
242  else error(E_NONUMBER);
243 
244  if (isint(argv[7])) duration = (float)intval(argv[7]);
245  else if (isflt(argv[7])) duration = (float)fltval(argv[7]);
246  else error(E_NONUMBER);
247 
248  std::string err_str = std::string();
249  ret = tf->waitForTransform(target_frame, target_time,
250  source_frame, source_time,
251  fixed_frame,
252  ros::Duration(timeout), ros::Duration(duration),
253  &err_str);
254  if(!ret) {
255  ROS_WARN_STREAM("waitForTransformFull failed! : " << err_str);
256  }
257  ROS_DEBUG_STREAM("waitForTransformFull : "
258  << "target_frame : " << target_frame
259  << "target_time : " << target_time
260  << "source_frame : " << source_frame
261  << "source_time : " << source_time
262  << "fixed_frame : " << fixed_frame
263  << "timeout : " << timeout
264  << "duration : " << duration
265  << "return : " << ret);
266 
267  return((ret==true)?(T):(NIL));
268 }
269 
271 {
272  ckarg(4);
274  std::string target_frame, source_frame;
275  ros::Time time;
276  bool ret;
277 
278  tf = (tf::Transformer *)(intval(argv[0]));
279  if (isstring(argv[1]))
280  target_frame = std::string((char*)(argv[1]->c.str.chars));
281  else error(E_NOSTRING);
282 
283  if (isstring(argv[2]))
284  source_frame = std::string((char*)(argv[2]->c.str.chars));
285  else error(E_NOSTRING);
286 
287  set_ros_time(time,argv[3]);
288 
289  std::string err_str = std::string();
290  ret = tf->canTransform(target_frame, source_frame, time, &err_str);
291  if(!ret) {
292  ROS_WARN_STREAM("canTransform " << target_frame << " " << source_frame << " failed! : " << err_str);
293  }
294  ROS_DEBUG_STREAM("canTransform : "
295  << "target_frame : " << target_frame
296  << "source_frame : " << source_frame
297  << "time : " << time
298  << "return : " << ret);
299 
300  return((ret==true)?(T):(NIL));
301 }
302 
304 {
305  ckarg(7);
307  std::string target_frame, source_frame, fixed_frame;
308  ros::Time target_time, source_time;
309  bool ret;
310 
311  tf = (tf::Transformer *)(intval(argv[0]));
312  if (isstring(argv[1]))
313  target_frame = std::string((char*)(argv[1]->c.str.chars));
314  else error(E_NOSTRING);
315 
316  set_ros_time(target_time,argv[3]);
317 
318  if (isstring(argv[3]))
319  source_frame = std::string((char*)(argv[3]->c.str.chars));
320  else error(E_NOSTRING);
321 
322  set_ros_time(source_time,argv[4]);
323 
324  if (isstring(argv[5]))
325  fixed_frame = std::string((char*)(argv[5]->c.str.chars));
326  else error(E_NOSTRING);
327 
328  std::string err_str = std::string();
329  ret = tf->canTransform(target_frame, target_time,
330  source_frame, source_time,
331  fixed_frame, &err_str);
332  if(!ret) {
333  ROS_WARN_STREAM("canTransformFull " << target_frame << " " << source_frame << " failed! : " << err_str);
334  }
335  ROS_DEBUG_STREAM("canTransformFull : "
336  << "target_frame : " << target_frame
337  << "target_time : " << target_time
338  << "source_frame : " << source_frame
339  << "source_time : " << source_time
340  << "fixed_frame : " << fixed_frame
341  << "return : " << ret);
342 
343  return((ret==true)?(T):(NIL));
344 }
345 
347 {
348  ROS_ERROR("%s is not implemented yet", __PRETTY_FUNCTION__);
349  return(T);
350 }
351 
353 {
354  ckarg(1);
355  tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
356  tf->clear();
357  return(T);
358 }
359 
361 {
362  ckarg(2);
364  std::string frame_id;
365 
366  tf = (tf::Transformer *)(intval(argv[0]));
367  if (!isstring(argv[1])) error(E_NOSTRING);
368  frame_id = std::string((char*)(argv[1]->c.str.chars));
369  return(tf->frameExists(frame_id)?T:NIL);
370 }
371 
373 {
374  ckarg(1);
375  tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
376  std::vector< std::string > ids;
377  pointer str = NIL;
378 
379  tf->getFrameStrings(ids);
380  for (std::vector< std::string >::iterator s = ids.begin(); s != ids.end(); s++) {
381  str=cons(ctx,makestring((char *)(s->c_str()),s->length()),str);
382  }
383 
384  return(str);
385 }
386 
388 {
389  ckarg(3);
391  std::string source_frame, target_frame, error_string;
392 
393  tf = (tf::Transformer *)(intval(argv[0]));
394  if (!isstring(argv[1])) error(E_NOSTRING);
395  source_frame = std::string((char*)(argv[1]->c.str.chars));
396  if (!isstring(argv[2])) error(E_NOSTRING);
397  target_frame = std::string((char*)(argv[2]->c.str.chars));
398 
399  ros::Time time;
400  int r = tf->getLatestCommonTime(source_frame, target_frame, time, &error_string);
401  if ( r == 0 ) {
402  return(cons(ctx,makeint(time.sec),makeint(time.nsec)));
403  } else {
404  ROS_ERROR_STREAM("getLatestCommonTime " << target_frame << " " << source_frame << " failed! : " << error_string);
405  return(NIL);
406  }
407 }
408 
410 {
411  ckarg(4);
413  std::string target_frame, source_frame;
414  ros::Time time;
415 
416  tf = (tf::Transformer *)(intval(argv[0]));
417  if (!isstring(argv[1])) error(E_NOSTRING);
418  target_frame = std::string((char*)(argv[1]->c.str.chars));
419  if (!isstring(argv[2])) error(E_NOSTRING);
420  source_frame = std::string((char*)(argv[2]->c.str.chars));
421 
422  set_ros_time(time,argv[3]);
423 
424  tf::StampedTransform transform;
425  try {
426  tf->lookupTransform(target_frame, source_frame, time, transform);
427  } catch ( std::runtime_error e ) {
428  ROS_ERROR("%s",e.what()); return(NIL);
429  }
430 
431  pointer vs = makefvector(7); //pos[3] + rot[4](angle-axis quaternion)
432  vpush(vs);
433  tf::Vector3 p = transform.getOrigin();
434  tf::Quaternion q = transform.getRotation();
435  vs->c.fvec.fv[0] = p.getX();
436  vs->c.fvec.fv[1] = p.getY();
437  vs->c.fvec.fv[2] = p.getZ();
438  vs->c.fvec.fv[3] = q.getW();
439  vs->c.fvec.fv[4] = q.getX();
440  vs->c.fvec.fv[5] = q.getY();
441  vs->c.fvec.fv[6] = q.getZ();
442  vpop();
443  return(vs);
444 }
445 
447 {
448  ckarg(6);
450  std::string target_frame, source_frame, fixed_frame;
451  ros::Time target_time, source_time;
452 
453  tf = (tf::Transformer *)(intval(argv[0]));
454  if (!isstring(argv[1])) error(E_NOSTRING);
455  target_frame = std::string((char*)(argv[1]->c.str.chars));
456 
457  set_ros_time(target_time,argv[2]);
458 
459  if (!isstring(argv[3])) error(E_NOSTRING);
460  source_frame = std::string((char*)(argv[3]->c.str.chars));
461 
462  set_ros_time(source_time,argv[4]);
463 
464  if (!isstring(argv[5])) error(E_NOSTRING);
465  fixed_frame = std::string((char*)(argv[5]->c.str.chars));
466 
467  tf::StampedTransform transform;
468  try {
469  tf->lookupTransform(target_frame, target_time,
470  source_frame, source_time, fixed_frame, transform);
471  } catch ( std::runtime_error e ) {
472  ROS_ERROR("%s",e.what()); return(NIL);
473  }
474 
475  pointer vs = makefvector(7); //pos[3] + rot[4](angle-axis quaternion)
476  vpush(vs);
477  tf::Vector3 p = transform.getOrigin();
478  tf::Quaternion q = transform.getRotation();
479  vs->c.fvec.fv[0] = p.getX();
480  vs->c.fvec.fv[1] = p.getY();
481  vs->c.fvec.fv[2] = p.getZ();
482  vs->c.fvec.fv[3] = q.getW();
483  vs->c.fvec.fv[4] = q.getX();
484  vs->c.fvec.fv[5] = q.getY();
485  vs->c.fvec.fv[6] = q.getZ();
486  vpop();
487  return(vs);
488 }
489 
490 
492 {
493  ckarg(5); // tf, target_frame, time, frame_id,
494  // pose as float-vector. its vector is a vector
495  // appended position and angle-vector quaternion
497  if (!isstring(argv[1])) error(E_NOSTRING);
498  std::string target_frame = std::string((char*)(argv[1]->c.str.chars));
499  ros::Time tm;
500  set_ros_time(tm, argv[2]);
501 
502  if (!isstring(argv[3])) error(E_NOSTRING);
503  std::string frame_id = std::string((char*)(argv[3]->c.str.chars));
504 
505  geometry_msgs::PoseStamped input, output;
506  // setup input
507  input.pose.position.x = argv[4]->c.fvec.fv[0];
508  input.pose.position.y = argv[4]->c.fvec.fv[1];
509  input.pose.position.z = argv[4]->c.fvec.fv[2];
510  input.pose.orientation.w = argv[4]->c.fvec.fv[3]; // angle-vector format
511  input.pose.orientation.x = argv[4]->c.fvec.fv[4];
512  input.pose.orientation.y = argv[4]->c.fvec.fv[5];
513  input.pose.orientation.z = argv[4]->c.fvec.fv[6];
514  // input.header.
515  input.header.stamp = tm;
516  input.header.frame_id = frame_id;
517 
518  try {
519  tf->transformPose(target_frame, input, output);
520  } catch ( std::runtime_error e ) {
521  ROS_ERROR("%s",e.what()); return(NIL);
522  }
523 
524  pointer vs = makefvector(7); //pos[3] + rot[4](angle-axis quaternion)
525  vpush(vs);
526  vs->c.fvec.fv[0] = output.pose.position.x;
527  vs->c.fvec.fv[1] = output.pose.position.y;
528  vs->c.fvec.fv[2] = output.pose.position.z;
529  vs->c.fvec.fv[3] = output.pose.orientation.w;
530  vs->c.fvec.fv[4] = output.pose.orientation.x;
531  vs->c.fvec.fv[5] = output.pose.orientation.y;
532  vs->c.fvec.fv[6] = output.pose.orientation.z;
533  vpop();
534  return(vs);
535 }
536 
538 {
539  numunion nu;
540  ckarg(4);
542  std::string reference_frame, moving_frame;
543  float time = 0, duration = 0;
544 
545  tf = (tf::Transformer *)(intval(argv[0]));
546  if (!isstring(argv[1])) error(E_NOSTRING);
547  reference_frame = std::string((char*)(argv[1]->c.str.chars));
548 
549  if (!isstring(argv[2])) error(E_NOSTRING);
550  moving_frame = std::string((char*)(argv[2]->c.str.chars));
551 
552  if (isint(argv[3])) time = (float)intval(argv[3]);
553  else if (isflt(argv[3])) time = (float)fltval(argv[3]);
554  else error(E_NONUMBER);
555 
556  if (isint(argv[4])) duration = (float)intval(argv[4]);
557  else if (isflt(argv[4])) duration = (float)fltval(argv[4]);
558  else error(E_NONUMBER);
559 
560  geometry_msgs::Twist velocity;
561  // ROS_ERROR("%s is not implemented yet since lookupVelocity seems obsoluted", __PRETTY_FUNCTION__);
562  tf->lookupTwist(reference_frame, moving_frame, ros::Time(time), ros::Duration(duration), velocity);
563 
564  pointer vs = makefvector(6); //pos[3] + rot[3](angle-axis)
565  vpush(vs);
566  vs->c.fvec.fv[0] = velocity.linear.x;
567  vs->c.fvec.fv[1] = velocity.linear.y;
568  vs->c.fvec.fv[2] = velocity.linear.z;
569  vs->c.fvec.fv[3] = velocity.angular.x;
570  vs->c.fvec.fv[4] = velocity.angular.y;
571  vs->c.fvec.fv[5] = velocity.angular.z;
572  vpop();
573  return(vs);
574 }
575 
576 /* */
578 {
579  if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
580  numunion nu;
581  ckarg(2);
582  float cache_time = ckfltval(argv[0]);
583  bool spin_thread = ((argv[1]==T)?true:false);
584  return(makeint((eusinteger_t)(new tf::TransformListener(ros::Duration(cache_time), spin_thread))));
585 }
586 
588 {
589  ckarg(1);
591  delete(tf);
592  return(T);
593 }
594 
595 /* */
597 {
598  numunion nu;
599  ckarg(2);
601  tf = (tf::Transformer *)(intval(argv[0]));
602  float distance = ckfltval(argv[1]);
603 
604  tf->setExtrapolationLimit(ros::Duration(distance));
605  return(T);
606 }
607 
609 {
610  ckarg(3);
612  std::string frame_id, parent;
613  ros::Time time;
614 
615  tf = (tf::Transformer *)(intval(argv[0]));
616 
617  if (isstring(argv[1]))
618  frame_id = std::string((char*)(argv[1]->c.str.chars));
619  else error(E_NOSTRING);
620 
621  set_ros_time(time,argv[2]);
622 
623  try {
624  bool ret = tf->getParent(frame_id, time, parent);
625  return(ret?makestring((char *)parent.c_str(),parent.length()):NIL);
626  } catch ( std::runtime_error e ) {
627  ROS_ERROR("%s",e.what()); return(NIL);
628  }
629 }
630 
631 /* */
633 {
634  if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
636 }
637 
639 
640  /* ptr pos quarternion parent_frame_id, child_frame_id, time */
641  ckarg(6);
642 
644 
645  isintvector(argv[5]);
646  ros::Time tm;
647  tm.sec = argv[5]->c.ivec.iv[0];
648  tm.nsec = argv[5]->c.ivec.iv[1];
649 
650  eusfloat_t *pos, *quaternion;
651  std::string p_frame_id, c_frame_id;
652  isfltvector(argv[1]);
653  isfltvector(argv[2]);
654  isstring(argv[3]);
655  isstring(argv[4]);
656  pos = argv[1]->c.fvec.fv;
657  quaternion= argv[2]->c.fvec.fv;
658  p_frame_id = (char *)argv[3]->c.str.chars;
659  c_frame_id = (char *)argv[4]->c.str.chars;
660 
661  geometry_msgs::TransformStamped trans;
662  trans.header.stamp = tm;
663  trans.header.frame_id = p_frame_id;
664  trans.child_frame_id = c_frame_id;
665  trans.transform.translation.x = pos[0]/1000.0;
666  trans.transform.translation.y = pos[1]/1000.0;
667  trans.transform.translation.z = pos[2]/1000.0;
668 
669  trans.transform.rotation.w = quaternion[0];
670  trans.transform.rotation.x = quaternion[1];
671  trans.transform.rotation.y = quaternion[2];
672  trans.transform.rotation.z = quaternion[3];
673 
674  bc->sendTransform(trans);
675 
676  return (T);
677 }
678 
679 /* tf2 */
681 {
682  if(!ros::ok()) { error(E_USER, "You must call (ros::roseus \"nodename\") before creating the first NodeHandle"); }
683  /* &optional (ns "tf2_buffer_server") (check_frequency 10.0) (timeout_padding 2.0) */
684  numunion nu;
685  std::string ns_str ("tf2_buffer_server");
686  double check_frequency = 10.0;
687  ros::Duration timeout_padding(2.0);
688 
689  ckarg2(0, 3);
690  if (n > 0) {
691  if (isstring (argv[0])) {
692  ns_str.assign ((char *)(argv[0]->c.str.chars));
693  } else {
694  error(E_NOSTRING);
695  }
696  }
697  if (n > 1) {
698  check_frequency = ckfltval(argv[1]);
699  }
700  if (n > 2) {
701  eusfloat_t pd = ckfltval(argv[2]);
702  timeout_padding = ros::Duration(pd);
703  }
704 
705  return(makeint((eusinteger_t)(new tf2_ros::BufferClient (ns_str, check_frequency, timeout_padding))));
706 }
707 
709 {
710  ckarg(1);
711  tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
712  delete(tfbc);
713  return(T);
714 }
715 
717 {
718  ckarg2(1, 2);
719  tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
720  numunion nu;
721  bool ret;
722  if (n > 1) {
723  ros::Duration tm(ckfltval(argv[1]));
724  ret = tfbc->waitForServer(tm);
725  } else {
726  ret = tfbc->waitForServer();
727  }
728  return((ret==true)?(T):(NIL));
729 }
730 
732 {
733  ckarg2(4, 5);
734  tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
735  numunion nu;
736  std::string target_frame, source_frame;
737  ros::Time time;
738  ros::Duration timeout(0.0);
739  bool ret;
740 
741  if (isstring(argv[1])) {
742  char *cstr = (char*)(argv[1]->c.str.chars);
743  if (cstr[0] == '/') {
744  target_frame.assign((char *)(cstr+1));
745  } else {
746  target_frame.assign(cstr);
747  }
748  } else error(E_NOSTRING);
749 
750  if (isstring(argv[2])) {
751  char *cstr = (char*)(argv[2]->c.str.chars);
752  if (cstr[0] == '/') {
753  source_frame.assign((char *)(cstr+1));
754  } else {
755  source_frame.assign(cstr);
756  }
757  } else error(E_NOSTRING);
758 
759  set_ros_time(time, argv[3]);
760 
761  if (n > 4) {
762  timeout = ros::Duration(ckfltval(argv[4]));
763  }
764  //target_frame.
765  std::string err_str = std::string();
766  ret = tfbc->canTransform(target_frame, source_frame, time, timeout, &err_str);
767  if(!ret) {
768  ROS_WARN_STREAM("BufferClient::waitForTransform failed! : " << err_str);
769  }
770  ROS_DEBUG_STREAM("BufferClient::waitForTransform : "
771  << "target_frame : " << target_frame
772  << "source_frame : " << source_frame
773  << "time : " << time
774  << "timeout : " << timeout
775  << "return : " << ret);
776 
777  return((ret==true)?(T):(NIL));
778 }
779 
781 {
782  ckarg2(4, 5);
783  tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
784  numunion nu;
785  std::string target_frame, source_frame;
786  ros::Time time;
787  ros::Duration timeout(0.0);
788 
789  if (!isstring(argv[1])) error(E_NOSTRING);
790  target_frame = std::string((char*)(argv[1]->c.str.chars));
791 
792  if (!isstring(argv[2])) error(E_NOSTRING);
793  source_frame = std::string((char*)(argv[2]->c.str.chars));
794 
795  set_ros_time(time, argv[3]);
796 
797  if (n > 4) {
798  timeout = ros::Duration(ckfltval(argv[4]));
799  }
800 
801  geometry_msgs::TransformStamped trans;
802  try {
803  trans = tfbc->lookupTransform(target_frame, source_frame, time, timeout);
804  } catch (std::runtime_error e) {
805  ROS_ERROR("%s", e.what()); return(NIL);
806  }
807 
808  pointer vs = makefvector(7); //pos[3] + rot[4](angle-axis quaternion)
809  vpush(vs);
810  //trans.header.frame_id
811  //trans.child_frame_id
812  //trans.header.stamp --> ??
813  vs->c.fvec.fv[0] = trans.transform.translation.x;
814  vs->c.fvec.fv[1] = trans.transform.translation.y;
815  vs->c.fvec.fv[2] = trans.transform.translation.z;
816  vs->c.fvec.fv[3] = trans.transform.rotation.w;
817  vs->c.fvec.fv[4] = trans.transform.rotation.x;
818  vs->c.fvec.fv[5] = trans.transform.rotation.y;
819  vs->c.fvec.fv[6] = trans.transform.rotation.z;
820  vpop();
821 
822  return(vs);
823 }
824 
825 #include "defun.h"
826 pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env)
827 {
828  pointer rospkg,p=Spevalof(PACKAGE);
829  rospkg=findpkg(makestring("TF",2));
830  if (rospkg == 0) rospkg=makepkg(ctx,makestring("TF", 2),NIL,NIL);
831  Spevalof(PACKAGE)=rospkg;
832 
833  rospkg=findpkg(makestring("ROS",3));
834  if (rospkg == 0 ) {
835  ROS_ERROR("Coudld not found ROS package; Please load eusros.so");
836  exit(2);
837  }
838  Spevalof(PACKAGE)=rospkg;
839  defun(ctx,"EUSTF-TRANSFORMER",argv[0],(pointer (*)())EUSTF_TRANSFORMER,"A Class which provides coordinate transforms between any two frames in a system");
840  defun(ctx,"EUSTF-ALL-FRAMES-AS-STRING",argv[0],(pointer (*)())EUSTF_ALLFRAMESASSTRING,"A way to see what frames have been cached Useful for debugging");
841  defun(ctx,"EUSTF-SET-TRANSFORM",argv[0],(pointer (*)())EUSTF_SETTRANSFORM,"Add transform information to the tf data structure");
842  defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORM,"Block until a transform is possible or it times out");
843  defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORMFULL,"Block until a transform is possible or it times out");
844  defun(ctx,"EUSTF-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_CANTRANSFORM,"Test if a transform is possible");
845  defun(ctx,"EUSTF-CAN-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_CANTRANSFORMFULL,"Test if a transform is possible");
846  defun(ctx,"EUSTF-CHAIN",argv[0],(pointer (*)())EUSTF_CHAIN,"Debugging function that will print the spanning chain of transforms");
847  defun(ctx,"EUSTF-CLEAR",argv[0],(pointer (*)())EUSTF_CLEAR,"Clear all data");
848  defun(ctx,"EUSTF-FRAME-EXISTS",argv[0],(pointer (*)())EUSTF_FRAMEEXISTS,"Check if a frame exists in the tree");
849  defun(ctx,"EUSTF-GET-FRAME-STRINGS",argv[0],(pointer (*)())EUSTF_GETFRAMESTRINGS,"A way to get a std::vector of available frame ids");
850  defun(ctx,"EUSTF-GET-LATEST-COMMON-TIME",argv[0],(pointer (*)())EUSTF_GETLATERSTCOMMONTIME,"Return the latest rostime which is common across the spanning set zero if fails to cross");
851  defun(ctx,"EUSTF-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID");
852  defun(ctx,"EUSTF-LOOKUP-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORMFULL,"Get the transform between two frames by frame ID");
853  defun(ctx,"EUSTF-TRANSFORM-POSE",argv[0],(pointer (*)())EUSTF_TRANSFORMPOSE,"Transform a Stamped Pose into the target frame This can throw anything a lookupTransform can throw as well as tf::InvalidArgument");
854  defun(ctx,"EUSTF-LOOKUP-VELOCITY",argv[0],(pointer (*)())EUSTF_LOOKUPVELOCITY,"Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point");
855  /* */
856  defun(ctx,"EUSTF-TRANSFORM-LISTENER",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER,"This class inherits from Transformer and automatically subscribes to ROS transform messages");
857  defun(ctx,"EUSTF-TRANSFORM-LISTENER-DISPOSE",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER_DISPOSE,"Destructor for TransformListener");
858 
859  /* */
860  defun(ctx,"EUSTF-SET-EXTRAPOLATION-LIMIT",argv[0],(pointer (*)())EUSTF_SETEXTRAPOLATIONLIMIT,"Set the distance which tf is allow to extrapolate");
861  defun(ctx,"EUSTF-GET-PARENT",argv[0],(pointer (*)())EUSTF_GETPARENT,"Fill the parent of a frame");
862  /* */
863  defun(ctx,"EUSTF-TRANSFORM-BROADCASTER",argv[0],(pointer (*)())EUSTF_TRANSFORM_BROADCASTER,"This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message");
864  defun(ctx,"EUSTF-SEND-TRANSFORM",argv[0],(pointer (*)())EUSTF_SEND_TRANSFORM,"Send a StampedTransform The stamped data structure includes frame_id, and time, and parent_id already");
865 
866  /* tf2 */
867  defun(ctx,"EUSTF-BUFFER-CLIENT",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT,"Action client-based implementation of the tf2_ros::BufferInterface abstract data type. BufferClient uses actionlib to coordinate waiting for available transforms.");
868  defun(ctx,"EUSTF-BUFFER-CLIENT-DISPOSE",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT_DISPOSE,"tf2 BufferClient destructor");
869  defun(ctx,"EUSTF-TF2-WAIT-FOR-SERVER",argv[0],(pointer (*)())EUSTF_TFBC_WAITFORSERVER,"Block until the action server is ready to respond to requests");
870  defun(ctx,"EUSTF-TF2-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_CANTRANSFORM,"Test if a transform is possible");
871  defun(ctx,"EUSTF-TF2-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_LOOKUPTRANSFORM,"Get the transform between two frames by frame ID");
872 
873  pointer_update(Spevalof(PACKAGE),p);
874  return 0;
875 }
bool getParent(const std::string &frame_id, ros::Time time, std::string &parent) const
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
pointer makeint(eusinteger_t v)
std::string allFramesAsString() const
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
pointer EUSTF_BUFFER_CLIENT_DISPOSE(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:708
Quaternion getRotation() const
struct string str
byte chars[1]
pointer EUSTF_TRANSFORM_LISTENER(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:577
pointer T
pointer EUSTF_LOOKUPTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:409
float fv[1]
pointer makepkg(context *, pointer, pointer, pointer)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
pointer EUSTF_WAITFORTRANSFORMFULL(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:213
pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env)
Definition: eustf.cpp:826
pointer makefvector(int)
bool setTransform(const StampedTransform &transform, const std::string &authority="default_authority")
void register_eustf()
Definition: eustf.cpp:90
ROS_INFO ROS_ERROR int n
Definition: roseus.cpp:818
E_USER
ckarg(2)
void add_module_initializer(char *, pointer(*)())
pointer EUSTF_TRANSFORMER(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:118
float ckfltval()
pointer EUSTF_ALLFRAMESASSTRING(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:127
struct intvector ivec
pointer EUSTF_CHAIN(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:346
pointer EUSTF_LOOKUPVELOCITY(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:537
#define string
Definition: eustf.cpp:81
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
union cell::cellunion c
pointer EUSTF_TRANSFORMPOSE(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:491
std::string child_frame_id_
ROS_INFO ROS_ERROR int pointer * argv
Definition: roseus.cpp:819
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0), std::string *errstr=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & getW() const
void lookupTwist(const std::string &tracking_frame, const std::string &observation_frame, const std::string &reference_frame, const tf::Point &reference_point, const std::string &reference_point_frame, const ros::Time &time, const ros::Duration &averaging_interval, geometry_msgs::Twist &twist) const
E_NOSTRING
pointer EUSTF_TRANSFORM_LISTENER_DISPOSE(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:587
pointer EUSTF_SETTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:135
pointer EUSTF_WAITFORTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:166
pointer EUSTF_TRANSFORM_BROADCASTER(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:632
pointer EUSTF_CLEAR(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:352
pointer EUSTF_CANTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:270
ROSCPP_DECL bool ok()
short s
void sendTransform(const StampedTransform &transform)
bool frameExists(const std::string &frame_id_str) const
pointer EUSTF_GETPARENT(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:608
pointer EUSTF_GETFRAMESTRINGS(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:372
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
long eusinteger_t
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0)) const
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
pointer defun(context *, char *, pointer, pointer(*)(), char *)
void getFrameStrings(std::vector< std::string > &ids) const
pointer PACKAGE
E_NONUMBER
pointer EUSTF_SETEXTRAPOLATIONLIMIT(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:596
pointer EUSTF_CANTRANSFORMFULL(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:303
int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
float fltval()
long iv[1]
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
pointer makestring(char *, int)
pointer EUSTF_TFBC_WAITFORSERVER(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:716
pointer EUSTF_TFBC_LOOKUPTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:780
pointer findpkg()
E_NOVECTOR
pointer EUSTF_SEND_TRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:638
#define ROS_ERROR_STREAM(args)
eusinteger_t intval(pointer p)
pointer EUSTF_GETLATERSTCOMMONTIME(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:387
double eusfloat_t
pointer EUSTF_LOOKUPTRANSFORMFULL(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:446
pointer EUSTF_BUFFER_CLIENT(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:680
pointer NIL
pointer EUSTF_FRAMEEXISTS(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:360
#define ROS_ERROR(...)
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void setExtrapolationLimit(const ros::Duration &distance)
std::string frame_id_
pointer length
pointer EUSTF_TFBC_CANTRANSFORM(register context *ctx, int n, pointer *argv)
Definition: eustf.cpp:731
#define set_ros_time(time, argv)
Definition: eustf.cpp:109
struct floatvector fvec


roseus
Author(s): Kei Okada
autogenerated on Thu Feb 2 2023 03:18:20