55 #include <boost/thread/mutex.hpp> 56 #include <boost/thread/condition.hpp> 57 #include <boost/shared_ptr.hpp> 72 #ifdef TF2_ROS_VERSION_3 // if this is groovy 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 91 char modname[] =
"___eustf";
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]; \ 122 bool interpolating = ((argv[0]==
T)?
true:
false);
123 float cache_time =
ckfltval(argv[1]);
143 isintvector(argv[3]);
154 transform.
setOrigin(tf::Vector3(pos[0]/1000.0, pos[1]/1000.0, pos[2]/1000.0));
173 float timeout = 0, duration = 0;
177 if (isstring(argv[1]))
181 if (isstring(argv[2]))
182 source_frame =
std::string((
char*)(argv[2]->c.str.chars));
187 if (isint(argv[4])) timeout = (float)
intval(argv[4]);
188 else if (isflt(argv[4])) timeout = (
float)
fltval(argv[4]);
191 if (isint(argv[5])) duration = (float)
intval(argv[5]);
192 else if (isflt(argv[5])) duration = (
float)
fltval(argv[5]);
203 <<
"target_frame : " << target_frame
204 <<
"source_frame : " << source_frame
206 <<
"timeout : " << timeout
207 <<
"duration : " << duration
208 <<
"return : " << ret);
210 return((ret==
true)?(
T):(
NIL));
218 std::string target_frame, source_frame, fixed_frame;
220 float timeout = 0, duration = 0;
224 if (isstring(argv[1]))
230 if (isstring(argv[3]))
231 source_frame =
std::string((
char*)(argv[3]->c.str.chars));
236 if (isstring(argv[5]))
237 fixed_frame =
std::string((
char*)(argv[5]->c.str.chars));
240 if (isint(argv[6])) timeout = (float)
intval(argv[6]);
241 else if (isflt(argv[6])) timeout = (
float)
fltval(argv[6]);
244 if (isint(argv[7])) duration = (float)
intval(argv[7]);
245 else if (isflt(argv[7])) duration = (
float)
fltval(argv[7]);
250 source_frame, source_time,
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);
267 return((ret==
true)?(
T):(
NIL));
279 if (isstring(argv[1]))
283 if (isstring(argv[2]))
284 source_frame =
std::string((
char*)(argv[2]->c.str.chars));
290 ret = tf->
canTransform(target_frame, source_frame, time, &err_str);
292 ROS_WARN_STREAM(
"canTransform " << target_frame <<
" " << source_frame <<
" failed! : " << err_str);
295 <<
"target_frame : " << target_frame
296 <<
"source_frame : " << source_frame
298 <<
"return : " << ret);
300 return((ret==
true)?(
T):(
NIL));
307 std::string target_frame, source_frame, fixed_frame;
312 if (isstring(argv[1]))
318 if (isstring(argv[3]))
319 source_frame =
std::string((
char*)(argv[3]->c.str.chars));
324 if (isstring(argv[5]))
325 fixed_frame =
std::string((
char*)(argv[5]->c.str.chars));
330 source_frame, source_time,
331 fixed_frame, &err_str);
333 ROS_WARN_STREAM(
"canTransformFull " << target_frame <<
" " << source_frame <<
" failed! : " << err_str);
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);
343 return((ret==
true)?(
T):(
NIL));
348 ROS_ERROR(
"%s is not implemented yet", __PRETTY_FUNCTION__);
368 frame_id =
std::string((
char*)(argv[1]->c.str.chars));
376 std::vector< std::string > ids;
380 for (std::vector< std::string >::iterator
s = ids.begin();
s != ids.end();
s++) {
391 std::string source_frame, target_frame, error_string;
395 source_frame =
std::string((
char*)(argv[1]->c.str.chars));
397 target_frame =
std::string((
char*)(argv[2]->c.str.chars));
404 ROS_ERROR_STREAM(
"getLatestCommonTime " << target_frame <<
" " << source_frame <<
" failed! : " << error_string);
418 target_frame =
std::string((
char*)(argv[1]->c.str.chars));
420 source_frame =
std::string((
char*)(argv[2]->c.str.chars));
427 }
catch ( std::runtime_error e ) {
450 std::string target_frame, source_frame, fixed_frame;
455 target_frame =
std::string((
char*)(argv[1]->c.str.chars));
460 source_frame =
std::string((
char*)(argv[3]->c.str.chars));
465 fixed_frame =
std::string((
char*)(argv[5]->c.str.chars));
470 source_frame, source_time, fixed_frame, transform);
471 }
catch ( std::runtime_error e ) {
505 geometry_msgs::PoseStamped input, output;
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];
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];
515 input.header.stamp = tm;
516 input.header.frame_id = frame_id;
520 }
catch ( std::runtime_error e ) {
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;
543 float time = 0, duration = 0;
547 reference_frame =
std::string((
char*)(argv[1]->c.str.chars));
550 moving_frame =
std::string((
char*)(argv[2]->c.str.chars));
552 if (isint(argv[3])) time = (float)
intval(argv[3]);
553 else if (isflt(argv[3])) time = (
float)
fltval(argv[3]);
556 if (isint(argv[4])) duration = (float)
intval(argv[4]);
557 else if (isflt(argv[4])) duration = (
float)
fltval(argv[4]);
560 geometry_msgs::Twist velocity;
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;
579 if( !
ros::ok() ) {
error(
E_USER,
"You must call ros::init() before creating the first NodeHandle"); }
582 float cache_time =
ckfltval(argv[0]);
583 bool spin_thread = ((argv[1]==
T)?
true:
false);
617 if (isstring(argv[1]))
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 ) {
634 if( !
ros::ok() ) {
error(
E_USER,
"You must call ros::init() before creating the first NodeHandle"); }
645 isintvector(argv[5]);
652 isfltvector(argv[1]);
653 isfltvector(argv[2]);
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;
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;
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];
682 if(!
ros::ok()) {
error(
E_USER,
"You must call (ros::roseus \"nodename\") before creating the first NodeHandle"); }
686 double check_frequency = 10.0;
691 if (isstring (argv[0])) {
692 ns_str.assign ((
char *)(argv[0]->c.str.chars));
698 check_frequency =
ckfltval(argv[1]);
728 return((ret==
true)?(
T):(
NIL));
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));
746 target_frame.assign(cstr);
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));
755 source_frame.assign(cstr);
766 ret = tfbc->
canTransform(target_frame, source_frame, time, timeout, &err_str);
768 ROS_WARN_STREAM(
"BufferClient::waitForTransform failed! : " << err_str);
771 <<
"target_frame : " << target_frame
772 <<
"source_frame : " << source_frame
774 <<
"timeout : " << timeout
775 <<
"return : " << ret);
777 return((ret==
true)?(
T):(
NIL));
790 target_frame =
std::string((
char*)(argv[1]->c.str.chars));
793 source_frame =
std::string((
char*)(argv[2]->c.str.chars));
801 geometry_msgs::TransformStamped trans;
803 trans = tfbc->
lookupTransform(target_frame, source_frame, time, timeout);
804 }
catch (std::runtime_error e) {
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;
835 ROS_ERROR(
"Coudld not found ROS package; Please load eusros.so");
839 defun(ctx,
"EUSTF-TRANSFORMER",argv[0],(
pointer (*)())
EUSTF_TRANSFORMER,
"A Class which provides coordinate transforms between any two frames in a system");
846 defun(ctx,
"EUSTF-CHAIN",argv[0],(
pointer (*)())
EUSTF_CHAIN,
"Debugging function that will print the spanning chain of transforms");
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");
856 defun(ctx,
"EUSTF-TRANSFORM-LISTENER",argv[0],(
pointer (*)())
EUSTF_TRANSFORM_LISTENER,
"This class inherits from Transformer and automatically subscribes to ROS transform messages");
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");
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.");
873 pointer_update(Spevalof(
PACKAGE),p);
pointer makeint(eusinteger_t v)
pointer EUSTF_BUFFER_CLIENT_DISPOSE(register context *ctx, int n, pointer *argv)
pointer EUSTF_TRANSFORM_LISTENER(register context *ctx, int n, pointer *argv)
pointer EUSTF_LOOKUPTRANSFORM(register context *ctx, int n, pointer *argv)
pointer makepkg(context *, pointer, pointer, pointer)
pointer EUSTF_WAITFORTRANSFORMFULL(register context *ctx, int n, pointer *argv)
pointer ___eustf(register context *ctx, int n, pointer *argv, pointer env)
void add_module_initializer(char *, pointer(*)())
pointer EUSTF_TRANSFORMER(register context *ctx, int n, pointer *argv)
pointer EUSTF_ALLFRAMESASSTRING(register context *ctx, int n, pointer *argv)
pointer EUSTF_CHAIN(register context *ctx, int n, pointer *argv)
pointer EUSTF_LOOKUPVELOCITY(register context *ctx, int n, pointer *argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
pointer EUSTF_TRANSFORMPOSE(register context *ctx, int n, pointer *argv)
ROS_INFO ROS_ERROR int pointer * argv
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
pointer EUSTF_TRANSFORM_LISTENER_DISPOSE(register context *ctx, int n, pointer *argv)
pointer EUSTF_SETTRANSFORM(register context *ctx, int n, pointer *argv)
pointer EUSTF_WAITFORTRANSFORM(register context *ctx, int n, pointer *argv)
pointer EUSTF_TRANSFORM_BROADCASTER(register context *ctx, int n, pointer *argv)
pointer EUSTF_CLEAR(register context *ctx, int n, pointer *argv)
pointer EUSTF_CANTRANSFORM(register context *ctx, int n, pointer *argv)
pointer EUSTF_GETPARENT(register context *ctx, int n, pointer *argv)
pointer EUSTF_GETFRAMESTRINGS(register context *ctx, int n, pointer *argv)
pointer error(enum errorcode ec,...) pointer error(va_alist) va_dcl
#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
pointer defun(context *, char *, pointer, pointer(*)(), char *)
pointer EUSTF_SETEXTRAPOLATIONLIMIT(register context *ctx, int n, pointer *argv)
pointer EUSTF_CANTRANSFORMFULL(register context *ctx, int n, pointer *argv)
pointer makestring(char *, int)
pointer EUSTF_TFBC_WAITFORSERVER(register context *ctx, int n, pointer *argv)
pointer EUSTF_TFBC_LOOKUPTRANSFORM(register context *ctx, int n, pointer *argv)
pointer EUSTF_SEND_TRANSFORM(register context *ctx, int n, pointer *argv)
#define ROS_ERROR_STREAM(args)
eusinteger_t intval(pointer p)
pointer EUSTF_GETLATERSTCOMMONTIME(register context *ctx, int n, pointer *argv)
pointer EUSTF_LOOKUPTRANSFORMFULL(register context *ctx, int n, pointer *argv)
pointer EUSTF_BUFFER_CLIENT(register context *ctx, int n, pointer *argv)
pointer EUSTF_FRAMEEXISTS(register context *ctx, int n, pointer *argv)
pointer EUSTF_TFBC_CANTRANSFORM(register context *ctx, int n, pointer *argv)
#define set_ros_time(time, argv)