00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
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
00072 #define class eus_class
00073 #define throw eus_throw
00074 #define export eus_export
00075 #define vector eus_vector
00076 #define string eus_string
00077
00078 #include "eus.h"
00079 extern "C" {
00080 pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env);
00081 void register_eustf(){
00082 char modname[] = "___eustf";
00083 return add_module_initializer(modname, (pointer (*)())___eustf);}
00084 }
00085
00086 #undef class
00087 #undef throw
00088 #undef export
00089 #undef vector
00090 #undef string
00091
00092 using namespace ros;
00093 using namespace std;
00094
00095
00096
00097
00098
00099
00100 #define set_ros_time(time,argv) \
00101 if (isvector(argv) && (elmtypeof(argv)==ELM_INT)) { \
00102 time.sec = argv->c.ivec.iv[0]; \
00103 time.nsec = argv->c.ivec.iv[1]; \
00104 } else { \
00105 error(E_NOVECTOR); \
00106 }
00107
00108
00109 pointer EUSTF_TRANSFORMER(register context *ctx,int n,pointer *argv)
00110 {
00111 numunion nu;
00112 ckarg(2);
00113 bool interpolating = ((argv[0]==T)?true:false);
00114 float cache_time = ckfltval(argv[1]);
00115 return(makeint((eusinteger_t)(new tf::Transformer(interpolating, ros::Duration(cache_time)))));
00116 }
00117
00118 pointer EUSTF_ALLFRAMESASSTRING(register context *ctx,int n,pointer *argv)
00119 {
00120 ckarg(1);
00121 tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00122 string str = tf->allFramesAsString();
00123 return(makestring((char *)(str.c_str()), str.length()));
00124 }
00125
00126 pointer EUSTF_SETTRANSFORM(register context *ctx,int n,pointer *argv)
00127 {
00128 ckarg(7);
00129 tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00130 if (!isvector(argv[1])) error(E_NOVECTOR);
00131 if (!isvector(argv[2])) error(E_NOVECTOR);
00132 eusfloat_t *pos = argv[1]->c.fvec.fv;
00133 eusfloat_t *rot = argv[2]->c.fvec.fv;
00134 isintvector(argv[3]);
00135 eusinteger_t *stamp = argv[3]->c.ivec.iv;
00136 if (!isstring(argv[4])) error(E_NOSTRING);
00137 if (!isstring(argv[5])) error(E_NOSTRING);
00138 if (!isstring(argv[6])) error(E_NOSTRING);
00139 std::string frame_id = std::string((char*)(argv[4]->c.str.chars));
00140 std::string child_frame_id = std::string((char*)(argv[5]->c.str.chars));
00141 std::string authority= std::string((char*)(argv[6]->c.str.chars));
00142 tf::StampedTransform transform;
00143 transform.setOrigin(tf::Vector3(pos[0], pos[1], pos[2]));
00144 transform.setRotation(tf::Quaternion(rot[3], rot[0], rot[1], rot[2]));
00145 transform.frame_id_ = frame_id;
00146 transform.child_frame_id_ = child_frame_id;
00147 transform.stamp_.sec = stamp[0];
00148 transform.stamp_.nsec = stamp[1];
00149 bool ret = tf->setTransform(transform, authority);
00150 return(ret?T:NIL);
00151 }
00152
00153 pointer EUSTF_WAITFORTRANSFORM(register context *ctx,int n,pointer *argv)
00154 {
00155 numunion nu;
00156 ckarg(6);
00157 tf::Transformer *tf;
00158 std::string target_frame, source_frame;
00159 ros::Time time;
00160 float timeout = 0, duration = 0;
00161 bool ret;
00162
00163 tf = (tf::Transformer *)(intval(argv[0]));
00164 if (isstring(argv[1]))
00165 target_frame = std::string((char*)(argv[1]->c.str.chars));
00166 else error(E_NOSTRING);
00167
00168 if (isstring(argv[2]))
00169 source_frame = std::string((char*)(argv[2]->c.str.chars));
00170 else error(E_NOSTRING);
00171
00172 set_ros_time(time,argv[3]);
00173
00174 if (isint(argv[4])) timeout = (float)intval(argv[4]);
00175 else if (isflt(argv[4])) timeout = (float)fltval(argv[4]);
00176 else error(E_NONUMBER);
00177
00178 if (isint(argv[5])) duration = (float)intval(argv[5]);
00179 else if (isflt(argv[5])) duration = (float)fltval(argv[5]);
00180 else error(E_NONUMBER);
00181
00182 std::string err_str = std::string();
00183 ret = tf->waitForTransform(target_frame, source_frame, time,
00184 ros::Duration(timeout), ros::Duration(duration),
00185 &err_str);
00186 if(!ret) {
00187 ROS_WARN_STREAM("waitForTransform failed! : " << err_str);
00188 }
00189 ROS_DEBUG_STREAM("waitForTransform : "
00190 << "target_frame : " << target_frame
00191 << "source_frame : " << source_frame
00192 << "time : " << time
00193 << "timeout : " << timeout
00194 << "duration : " << duration
00195 << "return : " << ret);
00196
00197 return((ret==true)?(T):(NIL));
00198 }
00199
00200 pointer EUSTF_WAITFORTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00201 {
00202 numunion nu;
00203 ckarg(8);
00204 tf::Transformer *tf;
00205 std::string target_frame, source_frame, fixed_frame;
00206 ros::Time target_time, source_time;
00207 float timeout = 0, duration = 0;
00208 bool ret;
00209
00210 tf = (tf::Transformer *)(intval(argv[0]));
00211 if (isstring(argv[1]))
00212 target_frame = std::string((char*)(argv[1]->c.str.chars));
00213 else error(E_NOSTRING);
00214
00215 set_ros_time(target_time,argv[2]);
00216
00217 if (isstring(argv[3]))
00218 source_frame = std::string((char*)(argv[3]->c.str.chars));
00219 else error(E_NOSTRING);
00220
00221 set_ros_time(source_time,argv[4]);
00222
00223 if (isstring(argv[5]))
00224 fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00225 else error(E_NOSTRING);
00226
00227 if (isint(argv[6])) timeout = (float)intval(argv[6]);
00228 else if (isflt(argv[6])) timeout = (float)fltval(argv[6]);
00229 else error(E_NONUMBER);
00230
00231 if (isint(argv[7])) duration = (float)intval(argv[7]);
00232 else if (isflt(argv[7])) duration = (float)fltval(argv[7]);
00233 else error(E_NONUMBER);
00234
00235 std::string err_str = std::string();
00236 ret = tf->waitForTransform(target_frame, target_time,
00237 source_frame, source_time,
00238 fixed_frame,
00239 ros::Duration(timeout), ros::Duration(duration),
00240 &err_str);
00241 if(!ret) {
00242 ROS_WARN_STREAM("waitForTransformFull failed! : " << err_str);
00243 }
00244 ROS_DEBUG_STREAM("waitForTransformFull : "
00245 << "target_frame : " << target_frame
00246 << "target_time : " << target_time
00247 << "source_frame : " << source_frame
00248 << "source_time : " << source_time
00249 << "fixed_frame : " << fixed_frame
00250 << "timeout : " << timeout
00251 << "duration : " << duration
00252 << "return : " << ret);
00253
00254 return((ret==true)?(T):(NIL));
00255 }
00256
00257 pointer EUSTF_CANTRANSFORM(register context *ctx,int n,pointer *argv)
00258 {
00259 ckarg(4);
00260 tf::Transformer *tf;
00261 std::string target_frame, source_frame;
00262 ros::Time time;
00263 bool ret;
00264
00265 tf = (tf::Transformer *)(intval(argv[0]));
00266 if (isstring(argv[1]))
00267 target_frame = std::string((char*)(argv[1]->c.str.chars));
00268 else error(E_NOSTRING);
00269
00270 if (isstring(argv[2]))
00271 source_frame = std::string((char*)(argv[2]->c.str.chars));
00272 else error(E_NOSTRING);
00273
00274 set_ros_time(time,argv[3]);
00275
00276 std::string err_str = std::string();
00277 ret = tf->canTransform(target_frame, source_frame, time, &err_str);
00278 if(!ret) {
00279 ROS_WARN_STREAM("canTransform " << target_frame << " " << source_frame << " failed! : " << err_str);
00280 }
00281 ROS_DEBUG_STREAM("canTransform : "
00282 << "target_frame : " << target_frame
00283 << "source_frame : " << source_frame
00284 << "time : " << time
00285 << "return : " << ret);
00286
00287 return((ret==true)?(T):(NIL));
00288 }
00289
00290 pointer EUSTF_CANTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00291 {
00292 ckarg(7);
00293 tf::Transformer *tf;
00294 std::string target_frame, source_frame, fixed_frame;
00295 ros::Time target_time, source_time;
00296 bool ret;
00297
00298 tf = (tf::Transformer *)(intval(argv[0]));
00299 if (isstring(argv[1]))
00300 target_frame = std::string((char*)(argv[1]->c.str.chars));
00301 else error(E_NOSTRING);
00302
00303 set_ros_time(target_time,argv[3]);
00304
00305 if (isstring(argv[3]))
00306 source_frame = std::string((char*)(argv[3]->c.str.chars));
00307 else error(E_NOSTRING);
00308
00309 set_ros_time(source_time,argv[4]);
00310
00311 if (isstring(argv[5]))
00312 fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00313 else error(E_NOSTRING);
00314
00315 std::string err_str = std::string();
00316 ret = tf->canTransform(target_frame, target_time,
00317 source_frame, source_time,
00318 fixed_frame, &err_str);
00319 if(!ret) {
00320 ROS_WARN_STREAM("canTransformFull " << target_frame << " " << source_frame << " failed! : " << err_str);
00321 }
00322 ROS_DEBUG_STREAM("canTransformFull : "
00323 << "target_frame : " << target_frame
00324 << "target_time : " << target_time
00325 << "source_frame : " << source_frame
00326 << "source_time : " << source_time
00327 << "fixed_frame : " << fixed_frame
00328 << "return : " << ret);
00329
00330 return((ret==true)?(T):(NIL));
00331 }
00332
00333 pointer EUSTF_CHAIN(register context *ctx,int n,pointer *argv)
00334 {
00335 ROS_ERROR("%s is not implemented yet", __PRETTY_FUNCTION__);
00336 return(T);
00337 }
00338
00339 pointer EUSTF_CLEAR(register context *ctx,int n,pointer *argv)
00340 {
00341 ckarg(1);
00342 tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00343 tf->clear();
00344 return(T);
00345 }
00346
00347 pointer EUSTF_FRAMEEXISTS(register context *ctx,int n,pointer *argv)
00348 {
00349 ckarg(2);
00350 tf::Transformer *tf;
00351 std::string frame_id;
00352
00353 tf = (tf::Transformer *)(intval(argv[0]));
00354 if (!isstring(argv[1])) error(E_NOSTRING);
00355 frame_id = std::string((char*)(argv[1]->c.str.chars));
00356 return(tf->frameExists(frame_id)?T:NIL);
00357 }
00358
00359 pointer EUSTF_GETFRAMESTRINGS(register context *ctx,int n,pointer *argv)
00360 {
00361 ckarg(1);
00362 tf::Transformer *tf = (tf::Transformer *)(intval(argv[0]));
00363 std::vector< std::string > ids;
00364 pointer str = NIL;
00365
00366 tf->getFrameStrings(ids);
00367 for (std::vector< std::string >::iterator s = ids.begin(); s != ids.end(); s++) {
00368 str=cons(ctx,makestring((char *)(s->c_str()),s->length()),str);
00369 }
00370
00371 return(str);
00372 }
00373
00374 pointer EUSTF_GETLATERSTCOMMONTIME(register context *ctx,int n,pointer *argv)
00375 {
00376 ckarg(3);
00377 tf::Transformer *tf;
00378 std::string source_frame, target_frame, error_string;
00379
00380 tf = (tf::Transformer *)(intval(argv[0]));
00381 if (!isstring(argv[1])) error(E_NOSTRING);
00382 source_frame = std::string((char*)(argv[1]->c.str.chars));
00383 if (!isstring(argv[2])) error(E_NOSTRING);
00384 target_frame = std::string((char*)(argv[2]->c.str.chars));
00385
00386 ros::Time time;
00387 int r = tf->getLatestCommonTime(source_frame, target_frame, time, &error_string);
00388 if ( r == 0 ) {
00389 return(cons(ctx,makeint(time.sec),makeint(time.nsec)));
00390 } else {
00391 ROS_ERROR_STREAM("getLatestCommonTime " << target_frame << " " << source_frame << " failed! : " << error_string);
00392 return(NIL);
00393 }
00394 }
00395
00396 pointer EUSTF_LOOKUPTRANSFORM(register context *ctx,int n,pointer *argv)
00397 {
00398 ckarg(4);
00399 tf::Transformer *tf;
00400 std::string target_frame, source_frame;
00401 ros::Time time;
00402
00403 tf = (tf::Transformer *)(intval(argv[0]));
00404 if (!isstring(argv[1])) error(E_NOSTRING);
00405 target_frame = std::string((char*)(argv[1]->c.str.chars));
00406 if (!isstring(argv[2])) error(E_NOSTRING);
00407 source_frame = std::string((char*)(argv[2]->c.str.chars));
00408
00409 set_ros_time(time,argv[3]);
00410
00411 tf::StampedTransform transform;
00412 try {
00413 tf->lookupTransform(target_frame, source_frame, time, transform);
00414 } catch ( std::runtime_error e ) {
00415 ROS_ERROR("%s",e.what()); return(NIL);
00416 }
00417
00418 pointer vs = makefvector(7);
00419 vpush(vs);
00420 tf::Vector3 p = transform.getOrigin();
00421 tf::Quaternion q = transform.getRotation();
00422 vs->c.fvec.fv[0] = p.getX();
00423 vs->c.fvec.fv[1] = p.getY();
00424 vs->c.fvec.fv[2] = p.getZ();
00425 vs->c.fvec.fv[3] = q.getW();
00426 vs->c.fvec.fv[4] = q.getX();
00427 vs->c.fvec.fv[5] = q.getY();
00428 vs->c.fvec.fv[6] = q.getZ();
00429 vpop();
00430 return(vs);
00431 }
00432
00433 pointer EUSTF_LOOKUPTRANSFORMFULL(register context *ctx,int n,pointer *argv)
00434 {
00435 ckarg(6);
00436 tf::Transformer *tf;
00437 std::string target_frame, source_frame, fixed_frame;
00438 ros::Time target_time, source_time;
00439
00440 tf = (tf::Transformer *)(intval(argv[0]));
00441 if (!isstring(argv[1])) error(E_NOSTRING);
00442 target_frame = std::string((char*)(argv[1]->c.str.chars));
00443
00444 set_ros_time(target_time,argv[2]);
00445
00446 if (!isstring(argv[3])) error(E_NOSTRING);
00447 source_frame = std::string((char*)(argv[3]->c.str.chars));
00448
00449 set_ros_time(source_time,argv[4]);
00450
00451 if (!isstring(argv[5])) error(E_NOSTRING);
00452 fixed_frame = std::string((char*)(argv[5]->c.str.chars));
00453
00454 tf::StampedTransform transform;
00455 try {
00456 tf->lookupTransform(target_frame, target_time,
00457 source_frame, source_time, fixed_frame, transform);
00458 } catch ( std::runtime_error e ) {
00459 ROS_ERROR("%s",e.what()); return(NIL);
00460 }
00461
00462 pointer vs = makefvector(7);
00463 vpush(vs);
00464 tf::Vector3 p = transform.getOrigin();
00465 tf::Quaternion q = transform.getRotation();
00466 vs->c.fvec.fv[0] = p.getX();
00467 vs->c.fvec.fv[1] = p.getY();
00468 vs->c.fvec.fv[2] = p.getZ();
00469 vs->c.fvec.fv[3] = q.getW();
00470 vs->c.fvec.fv[4] = q.getX();
00471 vs->c.fvec.fv[5] = q.getY();
00472 vs->c.fvec.fv[6] = q.getZ();
00473 vpop();
00474 return(vs);
00475 }
00476
00477
00478 pointer EUSTF_TRANSFORMPOSE(register context *ctx,int n,pointer *argv)
00479 {
00480 ckarg(5);
00481
00482
00483 tf::TransformListener *tf = (tf::TransformListener *)(intval(argv[0]));
00484 if (!isstring(argv[1])) error(E_NOSTRING);
00485 std::string target_frame = std::string((char*)(argv[1]->c.str.chars));
00486 ros::Time tm;
00487 set_ros_time(tm, argv[2]);
00488
00489 if (!isstring(argv[3])) error(E_NOSTRING);
00490 std::string frame_id = std::string((char*)(argv[3]->c.str.chars));
00491
00492 geometry_msgs::PoseStamped input, output;
00493
00494 input.pose.position.x = argv[4]->c.fvec.fv[0];
00495 input.pose.position.y = argv[4]->c.fvec.fv[1];
00496 input.pose.position.z = argv[4]->c.fvec.fv[2];
00497 input.pose.orientation.w = argv[4]->c.fvec.fv[3];
00498 input.pose.orientation.x = argv[4]->c.fvec.fv[4];
00499 input.pose.orientation.y = argv[4]->c.fvec.fv[5];
00500 input.pose.orientation.z = argv[4]->c.fvec.fv[6];
00501
00502 input.header.stamp = tm;
00503 input.header.frame_id = frame_id;
00504
00505 try {
00506 tf->transformPose(target_frame, input, output);
00507 } catch ( std::runtime_error e ) {
00508 ROS_ERROR("%s",e.what()); return(NIL);
00509 }
00510
00511 pointer vs = makefvector(7);
00512 vpush(vs);
00513 vs->c.fvec.fv[0] = output.pose.position.x;
00514 vs->c.fvec.fv[1] = output.pose.position.y;
00515 vs->c.fvec.fv[2] = output.pose.position.z;
00516 vs->c.fvec.fv[3] = output.pose.orientation.w;
00517 vs->c.fvec.fv[4] = output.pose.orientation.x;
00518 vs->c.fvec.fv[5] = output.pose.orientation.y;
00519 vs->c.fvec.fv[6] = output.pose.orientation.z;
00520 vpop();
00521 return(vs);
00522 }
00523
00524 pointer EUSTF_LOOKUPVELOCITY(register context *ctx,int n,pointer *argv)
00525 {
00526 numunion nu;
00527 ckarg(4);
00528 tf::Transformer *tf;
00529 std::string reference_frame, moving_frame;
00530 float time = 0, duration = 0;
00531
00532 tf = (tf::Transformer *)(intval(argv[0]));
00533 if (!isstring(argv[1])) error(E_NOSTRING);
00534 reference_frame = std::string((char*)(argv[1]->c.str.chars));
00535
00536 if (!isstring(argv[2])) error(E_NOSTRING);
00537 moving_frame = std::string((char*)(argv[2]->c.str.chars));
00538
00539 if (isint(argv[3])) time = (float)intval(argv[3]);
00540 else if (isflt(argv[3])) time = (float)fltval(argv[3]);
00541 else error(E_NONUMBER);
00542
00543 if (isint(argv[4])) duration = (float)intval(argv[4]);
00544 else if (isflt(argv[4])) duration = (float)fltval(argv[4]);
00545 else error(E_NONUMBER);
00546
00547 geometry_msgs::Twist velocity;
00548
00549 tf->lookupTwist(reference_frame, moving_frame, ros::Time(time), ros::Duration(duration), velocity);
00550
00551 pointer vs = makefvector(6);
00552 vpush(vs);
00553 vs->c.fvec.fv[0] = velocity.linear.x;
00554 vs->c.fvec.fv[1] = velocity.linear.y;
00555 vs->c.fvec.fv[2] = velocity.linear.z;
00556 vs->c.fvec.fv[3] = velocity.angular.x;
00557 vs->c.fvec.fv[4] = velocity.angular.y;
00558 vs->c.fvec.fv[5] = velocity.angular.z;
00559 vpop();
00560 return(vs);
00561 }
00562
00563
00564 pointer EUSTF_TRANSFORM_LISTENER(register context *ctx,int n,pointer *argv)
00565 {
00566 if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
00567 numunion nu;
00568 ckarg(2);
00569 float cache_time = ckfltval(argv[0]);
00570 bool spin_thread = ((argv[1]==T)?true:false);
00571 return(makeint((eusinteger_t)(new tf::TransformListener(ros::Duration(cache_time), spin_thread))));
00572 }
00573
00574 pointer EUSTF_TRANSFORM_LISTENER_DISPOSE(register context *ctx,int n,pointer *argv)
00575 {
00576 ckarg(1);
00577 tf::TransformListener *tf = (tf::TransformListener *)(intval(argv[0]));
00578 delete(tf);
00579 return(T);
00580 }
00581
00582
00583 pointer EUSTF_SETEXTRAPOLATIONLIMIT(register context *ctx,int n,pointer *argv)
00584 {
00585 numunion nu;
00586 ckarg(2);
00587 tf::Transformer *tf;
00588 tf = (tf::Transformer *)(intval(argv[0]));
00589 float distance = ckfltval(argv[1]);
00590
00591 tf->setExtrapolationLimit(ros::Duration(distance));
00592 return(T);
00593 }
00594
00595 pointer EUSTF_GETPARENT(register context *ctx,int n,pointer *argv)
00596 {
00597 ckarg(3);
00598 tf::Transformer *tf;
00599 std::string frame_id, parent;
00600 ros::Time time;
00601
00602 tf = (tf::Transformer *)(intval(argv[0]));
00603
00604 if (isstring(argv[1]))
00605 frame_id = std::string((char*)(argv[1]->c.str.chars));
00606 else error(E_NOSTRING);
00607
00608 set_ros_time(time,argv[2]);
00609
00610 try {
00611 bool ret = tf->getParent(frame_id, time, parent);
00612 return(ret?makestring((char *)parent.c_str(),parent.length()):NIL);
00613 } catch ( std::runtime_error e ) {
00614 ROS_ERROR("%s",e.what()); return(NIL);
00615 }
00616 }
00617
00618 pointer EUSTF_TRANSFORM_BROADCASTER(register context *ctx,int n,pointer *argv)
00619 {
00620 if( ! ros::ok() ) { error(E_USER,"You must call ros::init() before creating the first NodeHandle"); }
00621 return(makeint((eusinteger_t)(new tf::TransformBroadcaster())));
00622 }
00623
00624 pointer EUSTF_SEND_TRANSFORM(register context *ctx,int n,pointer *argv){
00625
00626
00627 ckarg(6);
00628
00629 tf::TransformBroadcaster *bc = (tf::TransformBroadcaster *)(intval(argv[0]));
00630
00631 isintvector(argv[5]);
00632 ros::Time tm;
00633 tm.sec = argv[5]->c.ivec.iv[0];
00634 tm.nsec = argv[5]->c.ivec.iv[1];
00635
00636 eusfloat_t *pos, *quaternion;
00637 std::string p_frame_id, c_frame_id;
00638 isfltvector(argv[1]);
00639 isfltvector(argv[2]);
00640 isstring(argv[3]);
00641 isstring(argv[4]);
00642 pos = argv[1]->c.fvec.fv;
00643 quaternion= argv[2]->c.fvec.fv;
00644 p_frame_id = (char *)argv[3]->c.str.chars;
00645 c_frame_id = (char *)argv[4]->c.str.chars;
00646
00647 geometry_msgs::TransformStamped trans;
00648 trans.header.stamp = tm;
00649 trans.header.frame_id = p_frame_id;
00650 trans.child_frame_id = c_frame_id;
00651 trans.transform.translation.x = pos[0]/1000.0;
00652 trans.transform.translation.y = pos[1]/1000.0;
00653 trans.transform.translation.z = pos[2]/1000.0;
00654
00655 trans.transform.rotation.w = quaternion[0];
00656 trans.transform.rotation.x = quaternion[1];
00657 trans.transform.rotation.y = quaternion[2];
00658 trans.transform.rotation.z = quaternion[3];
00659
00660 bc->sendTransform(trans);
00661
00662 return (T);
00663 }
00664
00665 pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env)
00666 {
00667 pointer rospkg,p=Spevalof(PACKAGE);
00668 rospkg=findpkg(makestring("TF",2));
00669 if (rospkg == 0) rospkg=makepkg(ctx,makestring("TF", 2),NIL,NIL);
00670 Spevalof(PACKAGE)=rospkg;
00671
00672 rospkg=findpkg(makestring("ROS",3));
00673 if (rospkg == 0 ) {
00674 ROS_ERROR("Coudld not found ROS package; Please load eusros.so");
00675 exit(2);
00676 }
00677 Spevalof(PACKAGE)=rospkg;
00678 defun(ctx,"EUSTF-TRANSFORMER",argv[0],(pointer (*)())EUSTF_TRANSFORMER);
00679 defun(ctx,"EUSTF-ALL-FRAMES-AS-STRING",argv[0],(pointer (*)())EUSTF_ALLFRAMESASSTRING);
00680 defun(ctx,"EUSTF-SET-TRANSFORM",argv[0],(pointer (*)())EUSTF_SETTRANSFORM);
00681 defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORM);
00682 defun(ctx,"EUSTF-WAIT-FOR-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_WAITFORTRANSFORMFULL);
00683 defun(ctx,"EUSTF-CAN-TRANSFORM",argv[0],(pointer (*)())EUSTF_CANTRANSFORM);
00684 defun(ctx,"EUSTF-CAN-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_CANTRANSFORMFULL);
00685 defun(ctx,"EUSTF-CHAIN",argv[0],(pointer (*)())EUSTF_CHAIN);
00686 defun(ctx,"EUSTF-CLEAR",argv[0],(pointer (*)())EUSTF_CLEAR);
00687 defun(ctx,"EUSTF-FRAME-EXISTS",argv[0],(pointer (*)())EUSTF_FRAMEEXISTS);
00688 defun(ctx,"EUSTF-GET-FRAME-STRINGS",argv[0],(pointer (*)())EUSTF_GETFRAMESTRINGS);
00689 defun(ctx,"EUSTF-GET-LATEST-COMMON-TIME",argv[0],(pointer (*)())EUSTF_GETLATERSTCOMMONTIME);
00690 defun(ctx,"EUSTF-LOOKUP-TRANSFORM",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORM);
00691 defun(ctx,"EUSTF-LOOKUP-TRANSFORM-FULL",argv[0],(pointer (*)())EUSTF_LOOKUPTRANSFORMFULL);
00692 defun(ctx,"EUSTF-TRANSFORM-POSE",argv[0],(pointer (*)())EUSTF_TRANSFORMPOSE);
00693 defun(ctx,"EUSTF-LOOKUP-VELOCITY",argv[0],(pointer (*)())EUSTF_LOOKUPVELOCITY);
00694
00695 defun(ctx,"EUSTF-TRANSFORM-LISTENER",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER);
00696 defun(ctx,"EUSTF-TRANSFORM-LISTENER-DISPOSE",argv[0],(pointer (*)())EUSTF_TRANSFORM_LISTENER_DISPOSE);
00697
00698
00699 defun(ctx,"EUSTF-SET-EXTRAPOLATION-LIMIT",argv[0],(pointer (*)())EUSTF_SETEXTRAPOLATIONLIMIT);
00700 defun(ctx,"EUSTF-GET-PARENT",argv[0],(pointer (*)())EUSTF_GETPARENT);
00701
00702 defun(ctx,"EUSTF-TRANSFORM-BROADCASTER",argv[0],(pointer (*)())EUSTF_TRANSFORM_BROADCASTER);
00703 defun(ctx,"EUSTF-SEND-TRANSFORM",argv[0],(pointer (*)())EUSTF_SEND_TRANSFORM);
00704
00705 pointer_update(Spevalof(PACKAGE),p);
00706 return 0;
00707 }