eustf.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, JSK Lab, the Univ. of Tokyo
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 // author: Ryohei Ueda
00036 #include <stdio.h>
00037 #include <stdlib.h>
00038 #include <unistd.h>
00039 #include <string.h>
00040 #include <signal.h>
00041 #include <math.h>
00042 #include <time.h>
00043 #include <pthread.h>
00044 #include <setjmp.h>
00045 #include <errno.h>
00046 
00047 #include <list>
00048 #include <vector>
00049 #include <set>
00050 #include <string>
00051 #include <map>
00052 #include <sstream>
00053 
00054 #include <cstdio>
00055 #include <boost/thread/mutex.hpp>
00056 #include <boost/thread/condition.hpp>
00057 #include <boost/shared_ptr.hpp>
00058 
00059 #include <ros/init.h>
00060 #include <ros/time.h>
00061 #include <ros/rate.h>
00062 #include <ros/master.h>
00063 #include <ros/this_node.h>
00064 #include <ros/node_handle.h>
00065 #include <ros/service.h>
00066 #include <tf/tf.h>
00067 #include <tf/transform_listener.h>
00068 #include <tf/transform_datatypes.h>
00069 #include <tf/transform_broadcaster.h>
00070 
00071 #include <tf2_ros/buffer_client.h>
00072 #ifdef TF2_ROS_VERSION_3 // if this is groovy
00073 #define tf2_ros tf2
00074 #endif
00075 
00076 // for eus.h
00077 #define class   eus_class
00078 #define throw   eus_throw
00079 #define export  eus_export
00080 #define vector  eus_vector
00081 #define string  eus_string
00082 
00083 #include "eus.h"
00084 extern "C" {
00085   pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env);
00086   void register_eustf(){
00087     char modname[] = "___eustf";
00088     return add_module_initializer(modname, (pointer (*)())___eustf);}
00089 }
00090 
00091 #undef class
00092 #undef throw
00093 #undef export
00094 #undef vector
00095 #undef string
00096 
00097 using namespace ros;
00098 using namespace std;
00099 
00100 
00101 /***********************************************************
00102  *   TF wrapper
00103  ************************************************************/
00104 
00105 #define set_ros_time(time,argv)                         \
00106   if (isvector(argv) && (elmtypeof(argv)==ELM_INT)) {   \
00107     time.sec  = argv->c.ivec.iv[0];                     \
00108     time.nsec = argv->c.ivec.iv[1];                     \
00109   } else {                                              \
00110     error(E_NOVECTOR);                                  \
00111   }
00112 
00113 /* */
00114 pointer EUSTF_TRANSFORMER(register context *ctx,int n,pointer *argv)
00115 {
00116   numunion nu;
00117   ckarg(2);
00118   bool interpolating = ((argv[0]==T)?true:false);
00119   float cache_time = ckfltval(argv[1]);
00120   return(makeint((eusinteger_t)(new tf::Transformer(interpolating, ros::Duration(cache_time)))));
00121 }
00122 
00123 pointer EUSTF_ALLFRAMESASSTRING(register context *ctx,int n,pointer *argv)
00124 {
00125   ckarg(1);
00126   tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00127   string str = tf->allFramesAsString();
00128   return(makestring((char *)(str.c_str()), str.length()));
00129 }
00130 
00131 pointer EUSTF_SETTRANSFORM(register context *ctx,int n,pointer *argv)
00132 {
00133   ckarg(7);
00134   tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00135   if (!isvector(argv[1])) error(E_NOVECTOR);
00136   if (!isvector(argv[2])) error(E_NOVECTOR);
00137   eusfloat_t *pos = argv[1]->c.fvec.fv;
00138   eusfloat_t *rot = argv[2]->c.fvec.fv;
00139   isintvector(argv[3]);
00140   eusinteger_t *stamp = argv[3]->c.ivec.iv;
00141   if (!isstring(argv[4])) error(E_NOSTRING);
00142   if (!isstring(argv[5])) error(E_NOSTRING);
00143   if (!isstring(argv[6])) error(E_NOSTRING);
00144   std::string frame_id = std::string((char*)(argv[4]->c.str.chars));
00145   std::string child_frame_id = std::string((char*)(argv[5]->c.str.chars));
00146   std::string authority= std::string((char*)(argv[6]->c.str.chars));
00147   tf::StampedTransform transform;
00148   transform.setOrigin(tf::Vector3(pos[0], pos[1], pos[2]));
00149   transform.setRotation(tf::Quaternion(rot[3], rot[0], rot[1], rot[2]));
00150   transform.frame_id_ = frame_id;
00151   transform.child_frame_id_ = child_frame_id;
00152   transform.stamp_.sec = stamp[0];
00153   transform.stamp_.nsec = stamp[1];
00154   bool ret = tf->setTransform(transform, authority);
00155   return(ret?T:NIL);
00156 }
00157 
00158 pointer EUSTF_WAITFORTRANSFORM(register context *ctx,int n,pointer *argv)
00159 {
00160   numunion nu;
00161   ckarg(6);
00162   tf::Transformer *tf;
00163   std::string target_frame, source_frame;
00164   ros::Time time;
00165   float timeout = 0, duration = 0;
00166   bool ret;
00167 
00168   tf = (tf::Transformer *)(intval(argv[0]));
00169   if (isstring(argv[1]))
00170     target_frame = std::string((char*)(argv[1]->c.str.chars));
00171   else error(E_NOSTRING);
00172 
00173   if (isstring(argv[2]))
00174     source_frame = std::string((char*)(argv[2]->c.str.chars));
00175   else error(E_NOSTRING);
00176 
00177   set_ros_time(time,argv[3]);
00178 
00179   if (isint(argv[4])) timeout = (float)intval(argv[4]);
00180   else if (isflt(argv[4])) timeout = (float)fltval(argv[4]);
00181   else error(E_NONUMBER);
00182 
00183   if (isint(argv[5])) duration = (float)intval(argv[5]);
00184   else if (isflt(argv[5])) duration = (float)fltval(argv[5]);
00185   else error(E_NONUMBER);
00186 
00187   std::string err_str = std::string();
00188   ret = tf->waitForTransform(target_frame, source_frame, time,
00189                              ros::Duration(timeout), ros::Duration(duration),
00190                              &err_str);
00191   if(!ret) {
00192     ROS_WARN_STREAM("waitForTransform failed! : " << err_str);
00193   }
00194   ROS_DEBUG_STREAM("waitForTransform : "
00195                    << "target_frame : " << target_frame
00196                    << "source_frame : " << source_frame
00197                    << "time : " << time
00198                    << "timeout : " << timeout
00199                    << "duration : " << duration
00200                    << "return : " << ret);
00201 
00202   return((ret==true)?(T):(NIL));
00203 }
00204 
00205 pointer EUSTF_WAITFORTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00206 {
00207   numunion nu;
00208   ckarg(8);
00209   tf::Transformer *tf;
00210   std::string target_frame, source_frame, fixed_frame;
00211   ros::Time target_time, source_time;
00212   float timeout = 0, duration = 0;
00213   bool ret;
00214 
00215   tf = (tf::Transformer *)(intval(argv[0]));
00216   if (isstring(argv[1]))
00217     target_frame = std::string((char*)(argv[1]->c.str.chars));
00218   else error(E_NOSTRING);
00219 
00220   set_ros_time(target_time,argv[2]);
00221 
00222   if (isstring(argv[3]))
00223     source_frame = std::string((char*)(argv[3]->c.str.chars));
00224   else error(E_NOSTRING);
00225 
00226   set_ros_time(source_time,argv[4]);
00227 
00228   if (isstring(argv[5]))
00229     fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00230   else error(E_NOSTRING);
00231 
00232   if (isint(argv[6])) timeout = (float)intval(argv[6]);
00233   else if (isflt(argv[6])) timeout = (float)fltval(argv[6]);
00234   else error(E_NONUMBER);
00235 
00236   if (isint(argv[7])) duration = (float)intval(argv[7]);
00237   else if (isflt(argv[7])) duration = (float)fltval(argv[7]);
00238   else error(E_NONUMBER);
00239 
00240   std::string err_str = std::string();
00241   ret = tf->waitForTransform(target_frame, target_time,
00242                              source_frame, source_time,
00243                              fixed_frame,
00244                              ros::Duration(timeout), ros::Duration(duration),
00245                              &err_str);
00246   if(!ret) {
00247     ROS_WARN_STREAM("waitForTransformFull failed! : " << err_str);
00248   }
00249   ROS_DEBUG_STREAM("waitForTransformFull : "
00250                    << "target_frame : " << target_frame
00251                    << "target_time : " << target_time
00252                    << "source_frame : " << source_frame
00253                    << "source_time : " << source_time
00254                    << "fixed_frame : " << fixed_frame
00255                    << "timeout : " << timeout
00256                    << "duration : " << duration
00257                    << "return : " << ret);
00258 
00259   return((ret==true)?(T):(NIL));
00260 }
00261 
00262 pointer EUSTF_CANTRANSFORM(register context *ctx,int n,pointer *argv)
00263 {
00264   ckarg(4);
00265   tf::Transformer *tf;
00266   std::string target_frame, source_frame;
00267   ros::Time time;
00268   bool ret;
00269 
00270   tf = (tf::Transformer *)(intval(argv[0]));
00271   if (isstring(argv[1]))
00272     target_frame = std::string((char*)(argv[1]->c.str.chars)); 
00273   else error(E_NOSTRING);
00274 
00275   if (isstring(argv[2]))
00276     source_frame = std::string((char*)(argv[2]->c.str.chars));
00277   else error(E_NOSTRING);
00278 
00279   set_ros_time(time,argv[3]);
00280 
00281   std::string err_str = std::string();
00282   ret = tf->canTransform(target_frame, source_frame, time, &err_str);
00283   if(!ret) {
00284     ROS_WARN_STREAM("canTransform " << target_frame << " " << source_frame << " failed! : " << err_str);
00285   }
00286   ROS_DEBUG_STREAM("canTransform : "
00287                    << "target_frame : " << target_frame
00288                    << "source_frame : " << source_frame
00289                    << "time : " << time
00290                    << "return : " << ret);
00291 
00292   return((ret==true)?(T):(NIL));
00293 }
00294 
00295 pointer EUSTF_CANTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00296 {
00297   ckarg(7);
00298   tf::Transformer *tf;
00299   std::string target_frame, source_frame, fixed_frame;
00300   ros::Time target_time, source_time;
00301   bool ret;
00302 
00303   tf = (tf::Transformer *)(intval(argv[0]));
00304   if (isstring(argv[1]))
00305     target_frame = std::string((char*)(argv[1]->c.str.chars));
00306   else error(E_NOSTRING);
00307 
00308   set_ros_time(target_time,argv[3]);
00309 
00310   if (isstring(argv[3]))
00311     source_frame = std::string((char*)(argv[3]->c.str.chars));
00312   else error(E_NOSTRING);
00313 
00314   set_ros_time(source_time,argv[4]);
00315 
00316   if (isstring(argv[5]))
00317     fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00318   else error(E_NOSTRING);
00319 
00320   std::string err_str = std::string();
00321   ret = tf->canTransform(target_frame, target_time,
00322                          source_frame, source_time,
00323                          fixed_frame, &err_str);
00324   if(!ret) {
00325     ROS_WARN_STREAM("canTransformFull " << target_frame << " " << source_frame << " failed! : " << err_str);
00326   }
00327   ROS_DEBUG_STREAM("canTransformFull : "
00328                    << "target_frame : " << target_frame
00329                    << "target_time : " << target_time
00330                    << "source_frame : " << source_frame
00331                    << "source_time : " << source_time
00332                    << "fixed_frame : " << fixed_frame
00333                    << "return : " << ret);
00334 
00335   return((ret==true)?(T):(NIL));
00336 }
00337 
00338 pointer EUSTF_CHAIN(register context *ctx,int n,pointer *argv)
00339 {
00340   ROS_ERROR("%s is not implemented yet", __PRETTY_FUNCTION__);
00341   return(T);
00342 }
00343 
00344 pointer EUSTF_CLEAR(register context *ctx,int n,pointer *argv)
00345 {
00346   ckarg(1);
00347   tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00348   tf->clear();
00349   return(T);
00350 }
00351 
00352 pointer EUSTF_FRAMEEXISTS(register context *ctx,int n,pointer *argv)
00353 {
00354   ckarg(2);
00355   tf::Transformer *tf;
00356   std::string frame_id;
00357 
00358   tf = (tf::Transformer *)(intval(argv[0]));
00359   if (!isstring(argv[1])) error(E_NOSTRING);
00360   frame_id = std::string((char*)(argv[1]->c.str.chars));
00361   return(tf->frameExists(frame_id)?T:NIL);
00362 }
00363 
00364 pointer EUSTF_GETFRAMESTRINGS(register context *ctx,int n,pointer *argv)
00365 {
00366   ckarg(1);
00367   tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00368   std::vector< std::string > ids;
00369   pointer str = NIL;
00370 
00371   tf->getFrameStrings(ids);
00372   for (std::vector< std::string >::iterator s = ids.begin(); s != ids.end(); s++) {
00373     str=cons(ctx,makestring((char *)(s->c_str()),s->length()),str);
00374   }
00375 
00376   return(str);
00377 }
00378 
00379 pointer EUSTF_GETLATERSTCOMMONTIME(register context *ctx,int n,pointer *argv)
00380 {
00381   ckarg(3);
00382   tf::Transformer *tf;
00383   std::string source_frame, target_frame, error_string;
00384 
00385   tf = (tf::Transformer *)(intval(argv[0]));
00386   if (!isstring(argv[1])) error(E_NOSTRING);
00387   source_frame = std::string((char*)(argv[1]->c.str.chars));
00388   if (!isstring(argv[2])) error(E_NOSTRING);
00389   target_frame = std::string((char*)(argv[2]->c.str.chars));
00390 
00391   ros::Time time;
00392   int r = tf->getLatestCommonTime(source_frame, target_frame, time, &error_string);
00393   if ( r == 0 ) {
00394     return(cons(ctx,makeint(time.sec),makeint(time.nsec)));
00395   } else {
00396     ROS_ERROR_STREAM("getLatestCommonTime " << target_frame << " " << source_frame << " failed! : " << error_string);
00397     return(NIL);
00398   }
00399 }
00400 
00401 pointer EUSTF_LOOKUPTRANSFORM(register context *ctx,int n,pointer *argv)
00402 {
00403   ckarg(4);
00404   tf::Transformer *tf;
00405   std::string target_frame, source_frame;
00406   ros::Time time;
00407 
00408   tf = (tf::Transformer *)(intval(argv[0]));
00409   if (!isstring(argv[1])) error(E_NOSTRING);
00410   target_frame = std::string((char*)(argv[1]->c.str.chars));
00411   if (!isstring(argv[2])) error(E_NOSTRING);
00412   source_frame = std::string((char*)(argv[2]->c.str.chars));
00413 
00414   set_ros_time(time,argv[3]);
00415 
00416   tf::StampedTransform transform;
00417   try {
00418     tf->lookupTransform(target_frame, source_frame, time, transform);
00419   } catch ( std::runtime_error e ) {
00420     ROS_ERROR("%s",e.what()); return(NIL);
00421   }
00422 
00423   pointer vs = makefvector(7);          //pos[3] + rot[4](angle-axis quaternion)
00424   vpush(vs);
00425   tf::Vector3 p = transform.getOrigin();
00426   tf::Quaternion q = transform.getRotation();
00427   vs->c.fvec.fv[0] = p.getX();
00428   vs->c.fvec.fv[1] = p.getY();
00429   vs->c.fvec.fv[2] = p.getZ();
00430   vs->c.fvec.fv[3] = q.getW();
00431   vs->c.fvec.fv[4] = q.getX();
00432   vs->c.fvec.fv[5] = q.getY();
00433   vs->c.fvec.fv[6] = q.getZ();
00434   vpop();
00435   return(vs);
00436 }
00437 
00438 pointer EUSTF_LOOKUPTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00439 {
00440   ckarg(6);
00441   tf::Transformer *tf;
00442   std::string target_frame, source_frame, fixed_frame;
00443   ros::Time target_time, source_time;
00444 
00445   tf = (tf::Transformer *)(intval(argv[0]));
00446   if (!isstring(argv[1])) error(E_NOSTRING);
00447   target_frame = std::string((char*)(argv[1]->c.str.chars));
00448 
00449   set_ros_time(target_time,argv[2]);
00450 
00451   if (!isstring(argv[3])) error(E_NOSTRING);
00452   source_frame = std::string((char*)(argv[3]->c.str.chars));
00453 
00454   set_ros_time(source_time,argv[4]);
00455 
00456   if (!isstring(argv[5])) error(E_NOSTRING);
00457   fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00458 
00459   tf::StampedTransform transform;
00460   try {
00461     tf->lookupTransform(target_frame, target_time,
00462                         source_frame, source_time, fixed_frame, transform);
00463   } catch ( std::runtime_error e ) {
00464     ROS_ERROR("%s",e.what()); return(NIL);
00465   }
00466 
00467   pointer vs = makefvector(7);          //pos[3] + rot[4](angle-axis quaternion)
00468   vpush(vs);
00469   tf::Vector3 p = transform.getOrigin();
00470   tf::Quaternion q = transform.getRotation();
00471   vs->c.fvec.fv[0] = p.getX();
00472   vs->c.fvec.fv[1] = p.getY();
00473   vs->c.fvec.fv[2] = p.getZ();
00474   vs->c.fvec.fv[3] = q.getW();
00475   vs->c.fvec.fv[4] = q.getX();
00476   vs->c.fvec.fv[5] = q.getY();
00477   vs->c.fvec.fv[6] = q.getZ();
00478   vpop();
00479   return(vs);
00480 }
00481 
00482 
00483 pointer EUSTF_TRANSFORMPOSE(register context *ctx,int n,pointer *argv)
00484 {
00485   ckarg(5);                     // tf, target_frame, time, frame_id, 
00486                                 // pose as float-vector. its vector is a vector
00487                                 // appended position and angle-vector quaternion
00488   tf::TransformListener *tf = (tf::TransformListener *)(intval(argv[0]));
00489   if (!isstring(argv[1])) error(E_NOSTRING);
00490   std::string target_frame = std::string((char*)(argv[1]->c.str.chars));
00491   ros::Time tm;
00492   set_ros_time(tm, argv[2]);
00493   
00494   if (!isstring(argv[3])) error(E_NOSTRING);
00495   std::string frame_id = std::string((char*)(argv[3]->c.str.chars));
00496   
00497   geometry_msgs::PoseStamped input, output;
00498   // setup input
00499   input.pose.position.x = argv[4]->c.fvec.fv[0];
00500   input.pose.position.y = argv[4]->c.fvec.fv[1];
00501   input.pose.position.z = argv[4]->c.fvec.fv[2];
00502   input.pose.orientation.w = argv[4]->c.fvec.fv[3]; // angle-vector format
00503   input.pose.orientation.x = argv[4]->c.fvec.fv[4];
00504   input.pose.orientation.y = argv[4]->c.fvec.fv[5];
00505   input.pose.orientation.z = argv[4]->c.fvec.fv[6];
00506   //  input.header.
00507   input.header.stamp = tm;
00508   input.header.frame_id = frame_id;
00509 
00510   try {
00511     tf->transformPose(target_frame, input, output);
00512   } catch ( std::runtime_error e ) {
00513     ROS_ERROR("%s",e.what()); return(NIL);
00514   }
00515 
00516   pointer vs = makefvector(7); //pos[3] + rot[4](angle-axis quaternion)
00517   vpush(vs);
00518   vs->c.fvec.fv[0] = output.pose.position.x;
00519   vs->c.fvec.fv[1] = output.pose.position.y;
00520   vs->c.fvec.fv[2] = output.pose.position.z;
00521   vs->c.fvec.fv[3] = output.pose.orientation.w;
00522   vs->c.fvec.fv[4] = output.pose.orientation.x;
00523   vs->c.fvec.fv[5] = output.pose.orientation.y;
00524   vs->c.fvec.fv[6] = output.pose.orientation.z;
00525   vpop();
00526   return(vs);
00527 }
00528 
00529 pointer EUSTF_LOOKUPVELOCITY(register context *ctx,int n,pointer *argv)
00530 {
00531   numunion nu;
00532   ckarg(4);
00533   tf::Transformer *tf;
00534   std::string reference_frame, moving_frame;
00535   float time = 0, duration = 0;
00536 
00537   tf = (tf::Transformer *)(intval(argv[0]));
00538   if (!isstring(argv[1])) error(E_NOSTRING);
00539   reference_frame = std::string((char*)(argv[1]->c.str.chars));
00540 
00541   if (!isstring(argv[2])) error(E_NOSTRING);
00542   moving_frame = std::string((char*)(argv[2]->c.str.chars));
00543 
00544   if (isint(argv[3])) time = (float)intval(argv[3]);
00545   else if (isflt(argv[3])) time = (float)fltval(argv[3]);
00546   else error(E_NONUMBER);
00547 
00548   if (isint(argv[4])) duration = (float)intval(argv[4]);
00549   else if (isflt(argv[4])) duration = (float)fltval(argv[4]);
00550   else error(E_NONUMBER);
00551 
00552   geometry_msgs::Twist velocity;
00553   // ROS_ERROR("%s is not implemented yet since lookupVelocity seems obsoluted", __PRETTY_FUNCTION__);
00554   tf->lookupTwist(reference_frame, moving_frame, ros::Time(time), ros::Duration(duration), velocity);
00555 
00556   pointer vs = makefvector(6);          //pos[3] + rot[3](angle-axis)
00557   vpush(vs);
00558   vs->c.fvec.fv[0] = velocity.linear.x;
00559   vs->c.fvec.fv[1] = velocity.linear.y;
00560   vs->c.fvec.fv[2] = velocity.linear.z;
00561   vs->c.fvec.fv[3] = velocity.angular.x;
00562   vs->c.fvec.fv[4] = velocity.angular.y;
00563   vs->c.fvec.fv[5] = velocity.angular.z;
00564   vpop();
00565   return(vs);
00566 }
00567 
00568 /* */
00569 pointer EUSTF_TRANSFORM_LISTENER(register context *ctx,int n,pointer *argv)
00570 {
00571   if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
00572   numunion nu;
00573   ckarg(2);
00574   float cache_time = ckfltval(argv[0]);
00575   bool spin_thread = ((argv[1]==T)?true:false);
00576   return(makeint((eusinteger_t)(new tf::TransformListener(ros::Duration(cache_time), spin_thread))));
00577 }
00578 
00579 pointer EUSTF_TRANSFORM_LISTENER_DISPOSE(register context *ctx,int n,pointer *argv)
00580 {
00581   ckarg(1);
00582   tf::TransformListener *tf = (tf::TransformListener *)(intval(argv[0]));
00583   delete(tf);
00584   return(T);
00585 }
00586 
00587 /* */
00588 pointer EUSTF_SETEXTRAPOLATIONLIMIT(register context *ctx,int n,pointer *argv)
00589 {
00590   numunion nu;
00591   ckarg(2);
00592   tf::Transformer *tf;
00593   tf = (tf::Transformer *)(intval(argv[0]));
00594   float distance = ckfltval(argv[1]);
00595 
00596   tf->setExtrapolationLimit(ros::Duration(distance));
00597   return(T);
00598 }
00599 
00600 pointer EUSTF_GETPARENT(register context *ctx,int n,pointer *argv)
00601 {
00602   ckarg(3);
00603   tf::Transformer *tf;
00604   std::string frame_id, parent;
00605   ros::Time time;
00606 
00607   tf = (tf::Transformer *)(intval(argv[0]));
00608 
00609   if (isstring(argv[1]))
00610     frame_id = std::string((char*)(argv[1]->c.str.chars));
00611   else error(E_NOSTRING);
00612 
00613   set_ros_time(time,argv[2]);
00614 
00615   try {
00616     bool ret = tf->getParent(frame_id, time, parent);
00617     return(ret?makestring((char *)parent.c_str(),parent.length()):NIL);
00618   } catch ( std::runtime_error e ) {
00619     ROS_ERROR("%s",e.what()); return(NIL);
00620   }
00621 }
00622 
00623 /* */
00624 pointer EUSTF_TRANSFORM_BROADCASTER(register context *ctx,int n,pointer *argv)
00625 {
00626   if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
00627   return(makeint((eusinteger_t)(new tf::TransformBroadcaster())));
00628 }
00629 
00630 pointer EUSTF_SEND_TRANSFORM(register context *ctx,int n,pointer *argv){
00631 
00632   /* ptr pos quarternion parent_frame_id, child_frame_id, time */
00633   ckarg(6);
00634 
00635   tf::TransformBroadcaster *bc = (tf::TransformBroadcaster *)(intval(argv[0]));
00636 
00637   isintvector(argv[5]);
00638   ros::Time tm;
00639   tm.sec = argv[5]->c.ivec.iv[0];
00640   tm.nsec = argv[5]->c.ivec.iv[1];
00641 
00642   eusfloat_t *pos, *quaternion;
00643   std::string p_frame_id, c_frame_id;
00644   isfltvector(argv[1]);
00645   isfltvector(argv[2]);
00646   isstring(argv[3]);
00647   isstring(argv[4]);
00648   pos = argv[1]->c.fvec.fv;
00649   quaternion= argv[2]->c.fvec.fv;
00650   p_frame_id = (char *)argv[3]->c.str.chars;
00651   c_frame_id = (char *)argv[4]->c.str.chars;
00652 
00653   geometry_msgs::TransformStamped trans;
00654   trans.header.stamp = tm;
00655   trans.header.frame_id = p_frame_id;
00656   trans.child_frame_id = c_frame_id;
00657   trans.transform.translation.x = pos[0]/1000.0;
00658   trans.transform.translation.y = pos[1]/1000.0;
00659   trans.transform.translation.z = pos[2]/1000.0;
00660 
00661   trans.transform.rotation.w = quaternion[0];
00662   trans.transform.rotation.x = quaternion[1];
00663   trans.transform.rotation.y = quaternion[2];
00664   trans.transform.rotation.z = quaternion[3];
00665 
00666   bc->sendTransform(trans);
00667 
00668   return (T);
00669 }
00670 
00671 /* tf2 */
00672 pointer EUSTF_BUFFER_CLIENT(register context *ctx,int n,pointer *argv)
00673 {
00674   if(!ros::ok()) { error(E_USER, "You must call (ros::roseus \"nodename\") before creating the first NodeHandle"); }
00675   /* &optional (ns "tf2_buffer_server") (check_frequency 10.0) (timeout_padding 2.0) */
00676   numunion nu;
00677   std::string ns_str ("tf2_buffer_server");
00678   double check_frequency = 10.0;
00679   ros::Duration timeout_padding(2.0);
00680 
00681   ckarg2(0, 3);
00682   if (n > 0) {
00683     if (isstring (argv[0])) {
00684       ns_str.assign ((char *)(argv[0]->c.str.chars));
00685     } else {
00686       error(E_NOSTRING);
00687     }
00688   }
00689   if (n > 1) {
00690     check_frequency = ckfltval(argv[1]);
00691   }
00692   if (n > 2) {
00693     eusfloat_t pd = ckfltval(argv[2]);
00694     timeout_padding = ros::Duration(pd);
00695   }
00696 
00697   return(makeint((eusinteger_t)(new tf2_ros::BufferClient (ns_str, check_frequency, timeout_padding))));
00698 }
00699 
00700 pointer EUSTF_BUFFER_CLIENT_DISPOSE(register context *ctx,int n,pointer *argv)
00701 {
00702   ckarg(1);
00703   tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
00704   delete(tfbc);
00705   return(T);
00706 }
00707 
00708 pointer EUSTF_TFBC_WAITFORSERVER(register context *ctx,int n,pointer *argv)
00709 {
00710   ckarg2(1, 2);
00711   tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
00712   numunion nu;
00713   bool ret;
00714   if (n > 1) {
00715     ros::Duration tm(ckfltval(argv[1]));
00716     ret = tfbc->waitForServer(tm);
00717   } else {
00718     ret = tfbc->waitForServer();
00719   }
00720   return((ret==true)?(T):(NIL));
00721 }
00722 
00723 pointer EUSTF_TFBC_CANTRANSFORM(register context *ctx,int n,pointer *argv)
00724 {
00725   ckarg2(4, 5);
00726   tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
00727   numunion nu;
00728   std::string target_frame, source_frame;
00729   ros::Time time;
00730   ros::Duration timeout(0.0);
00731   bool ret;
00732 
00733   if (isstring(argv[1])) {
00734     char *cstr = (char*)(argv[1]->c.str.chars);
00735     if (cstr[0] == '/') {
00736       target_frame.assign((char *)(cstr+1));
00737     } else {
00738       target_frame.assign(cstr);
00739     }
00740   } else error(E_NOSTRING);
00741 
00742   if (isstring(argv[2])) {
00743     char *cstr = (char*)(argv[2]->c.str.chars);
00744     if (cstr[0] == '/') {
00745       source_frame.assign((char *)(cstr+1));
00746     } else {
00747       source_frame.assign(cstr);
00748     }
00749   } else error(E_NOSTRING);
00750 
00751   set_ros_time(time, argv[3]);
00752 
00753   if (n > 4) {
00754     timeout = ros::Duration(ckfltval(argv[4]));
00755   }
00756   //target_frame.
00757   std::string err_str = std::string();
00758   ret = tfbc->canTransform(target_frame, source_frame, time, timeout, &err_str);
00759   if(!ret) {
00760     ROS_WARN_STREAM("BufferClient::waitForTransform failed! : " << err_str);
00761   }
00762   ROS_DEBUG_STREAM("BufferClient::waitForTransform : "
00763                    << "target_frame : " << target_frame
00764                    << "source_frame : " << source_frame
00765                    << "time : " << time
00766                    << "timeout : " << timeout
00767                    << "return : " << ret);
00768 
00769   return((ret==true)?(T):(NIL));
00770 }
00771 
00772 pointer EUSTF_TFBC_LOOKUPTRANSFORM(register context *ctx,int n,pointer *argv)
00773 {
00774   ckarg2(4, 5);
00775   tf2_ros::BufferClient *tfbc = (tf2_ros::BufferClient *)(intval(argv[0]));
00776   numunion nu;
00777   std::string target_frame, source_frame;
00778   ros::Time time;
00779   ros::Duration timeout(0.0);
00780 
00781   if (!isstring(argv[1])) error(E_NOSTRING);
00782   target_frame = std::string((char*)(argv[1]->c.str.chars));
00783 
00784   if (!isstring(argv[2])) error(E_NOSTRING);
00785   source_frame = std::string((char*)(argv[2]->c.str.chars));
00786 
00787   set_ros_time(time, argv[3]);
00788 
00789   if (n > 4) {
00790     timeout = ros::Duration(ckfltval(argv[4]));
00791   }
00792 
00793   geometry_msgs::TransformStamped trans;
00794   try {
00795     trans = tfbc->lookupTransform(target_frame, source_frame, time, timeout);
00796   } catch (std::runtime_error e) {
00797     ROS_ERROR("%s", e.what()); return(NIL);
00798   }
00799 
00800   pointer vs = makefvector(7);  //pos[3] + rot[4](angle-axis quaternion)
00801   vpush(vs);
00802   //trans.header.frame_id
00803   //trans.child_frame_id
00804   //trans.header.stamp --> ??
00805   vs->c.fvec.fv[0] = trans.transform.translation.x;
00806   vs->c.fvec.fv[1] = trans.transform.translation.y;
00807   vs->c.fvec.fv[2] = trans.transform.translation.z;
00808   vs->c.fvec.fv[3] = trans.transform.rotation.w;
00809   vs->c.fvec.fv[4] = trans.transform.rotation.x;
00810   vs->c.fvec.fv[5] = trans.transform.rotation.y;
00811   vs->c.fvec.fv[6] = trans.transform.rotation.z;
00812   vpop();
00813 
00814   return(vs);
00815 }
00816 
00817 pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env)
00818 {
00819   pointer rospkg,p=Spevalof(PACKAGE);
00820   rospkg=findpkg(makestring("TF",2));
00821   if (rospkg == 0) rospkg=makepkg(ctx,makestring("TF", 2),NIL,NIL);
00822   Spevalof(PACKAGE)=rospkg;
00823 
00824   rospkg=findpkg(makestring("ROS",3));
00825   if (rospkg == 0 ) {
00826     ROS_ERROR("Coudld not found ROS package; Please load eusros.so");
00827     exit(2);
00828   }
00829   Spevalof(PACKAGE)=rospkg;
00830   defun(ctx,"EUSTF-TRANSFORMER",argv[0],(pointer (*)())EUSTF_TRANSFORMER);
00831   defun(ctx,"EUSTF-ALL-FRAMES-AS-STRING",argv[0],(pointer (*)())EUSTF_ALLFRAMESASSTRING);
00832   defun(ctx,"EUSTF-SET-TRANSFORM",argv[0],(pointer (*)())EUSTF_SETTRANSFORM);
00833   defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORM);
00834   defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORMFULL);
00835   defun(ctx,"EUSTF-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_CANTRANSFORM);
00836   defun(ctx,"EUSTF-CAN-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_CANTRANSFORMFULL);
00837   defun(ctx,"EUSTF-CHAIN",argv[0],(pointer (*)())EUSTF_CHAIN);
00838   defun(ctx,"EUSTF-CLEAR",argv[0],(pointer (*)())EUSTF_CLEAR);
00839   defun(ctx,"EUSTF-FRAME-EXISTS",argv[0],(pointer (*)())EUSTF_FRAMEEXISTS);
00840   defun(ctx,"EUSTF-GET-FRAME-STRINGS",argv[0],(pointer (*)())EUSTF_GETFRAMESTRINGS);
00841   defun(ctx,"EUSTF-GET-LATEST-COMMON-TIME",argv[0],(pointer (*)())EUSTF_GETLATERSTCOMMONTIME);
00842   defun(ctx,"EUSTF-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORM);
00843   defun(ctx,"EUSTF-LOOKUP-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORMFULL);
00844   defun(ctx,"EUSTF-TRANSFORM-POSE",argv[0],(pointer (*)())EUSTF_TRANSFORMPOSE);
00845   defun(ctx,"EUSTF-LOOKUP-VELOCITY",argv[0],(pointer (*)())EUSTF_LOOKUPVELOCITY);
00846   /* */
00847   defun(ctx,"EUSTF-TRANSFORM-LISTENER",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER);
00848   defun(ctx,"EUSTF-TRANSFORM-LISTENER-DISPOSE",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER_DISPOSE);
00849 
00850   /* */
00851   defun(ctx,"EUSTF-SET-EXTRAPOLATION-LIMIT",argv[0],(pointer (*)())EUSTF_SETEXTRAPOLATIONLIMIT);
00852   defun(ctx,"EUSTF-GET-PARENT",argv[0],(pointer (*)())EUSTF_GETPARENT);
00853   /* */
00854   defun(ctx,"EUSTF-TRANSFORM-BROADCASTER",argv[0],(pointer (*)())EUSTF_TRANSFORM_BROADCASTER);
00855   defun(ctx,"EUSTF-SEND-TRANSFORM",argv[0],(pointer (*)())EUSTF_SEND_TRANSFORM);
00856 
00857   /* tf2 */
00858   defun(ctx,"EUSTF-BUFFER-CLIENT",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT);
00859   defun(ctx,"EUSTF-BUFFER-CLIENT-DISPOSE",argv[0],(pointer (*)())EUSTF_BUFFER_CLIENT_DISPOSE);
00860   defun(ctx,"EUSTF-TF2-WAIT-FOR-SERVER",argv[0],(pointer (*)())EUSTF_TFBC_WAITFORSERVER);
00861   defun(ctx,"EUSTF-TF2-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_CANTRANSFORM);
00862   defun(ctx,"EUSTF-TF2-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_TFBC_LOOKUPTRANSFORM);
00863 
00864   pointer_update(Spevalof(PACKAGE),p);
00865   return 0;
00866 }


roseus
Author(s): Kei Okada
autogenerated on Mon Oct 6 2014 01:19:15