$search
00001 /* 00002 * Copyright (c) 2009 Dejan Pangercic <pangercic -=- cs.tum.edu> 00003 * 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions are met: 00008 * 00009 * * Redistributions of source code must retain the above copyright 00010 * notice, this list of conditions and the following disclaimer. 00011 * * Redistributions in binary form must reproduce the above copyright 00012 * notice, this list of conditions and the following disclaimer in the 00013 * documentation and/or other materials provided with the distribution. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 00026 * 00027 * $Id: query_table_objects.cpp 17089 2009-06-15 18:52:12Z pangercic $ 00028 * 00029 */ 00030 00051 #include "ros/ros.h" 00052 #include "ros/node_handle.h" 00053 #include <mapping_srvs/FindTableId.h> 00054 #include <cstdlib> 00055 #include <ctype.h> 00056 #include <SWI-Prolog.h> 00057 extern "C" 00058 { 00059 using namespace mapping_srvs; 00060 00061 foreign_t 00062 pl_getPlaneClustersROS(term_t l) 00063 { 00064 int argc; 00065 argc=1; 00066 char **argv; 00067 argv = (char **)malloc(sizeof(char*)); 00068 argv[0] = (char *)malloc(sizeof(char) *2); 00069 argv[0][0] = 'a'; 00070 argv[0][1] = '\0'; 00071 ros::init(argc, argv, "query_table_objects"); 00072 ros::NodeHandle n; 00073 ros::ServiceClient client = n.serviceClient<FindTableId>("/table_object_detector_sick/table_object_detector"); 00074 FindTableId srv; 00075 term_t tmp = PL_new_term_ref(); 00076 float cluster[3]; 00077 // ROS_DEBUG(" srv.response.table.header.seq %u", srv.response.table.header.seq); 00078 if (client.call(srv)) 00079 { 00080 ROS_DEBUG("srv.response.id %ld", srv.response.id); 00081 //add response variables of choice 00082 if (!PL_unify_list(l, tmp, l) || 00083 !PL_unify_integer(tmp, srv.response.id)) 00084 PL_fail; 00085 //TODO: integrate table time stamps 00086 //ROS_DEBUG("Table seq: %d", srv.response.table.header.seq); 00087 // if (!PL_unify_list(l, tmp, l) || 00088 // !PL_unify_float(tmp, float(srv.response.table.header.stamp))) 00089 // PL_fail; 00090 //ROS_DEBUG("Table stamp: %f", srv.response.table.header.stamp); 00091 00092 for (unsigned int j = 0; j < srv.response.table.objects.size(); j++) 00093 { 00094 cluster[0] = srv.response.table.objects[j].center.x; 00095 cluster[1] = srv.response.table.objects[j].center.y; 00096 cluster[2] = srv.response.table.objects[j].center.z; 00097 ROS_DEBUG("cluster %f, %f, %f", cluster[0], cluster[1], cluster[2]); 00098 for (int i = 0; i < 3; i++) 00099 { 00100 if(!PL_unify_list(l, tmp, l) || !PL_unify_float(tmp, cluster[i])) 00101 { 00102 PL_fail; 00103 break; 00104 } 00105 } 00106 } 00107 return PL_unify_nil(l); 00108 } 00109 else 00110 { 00111 ROS_ERROR("Failed to call service /table_object_detector_sick/table_object_detector"); 00112 return -1; 00113 } 00114 free(argv[0]); 00115 free(argv); 00116 return 0; 00117 } 00118 00120 // register foreign functions 00122 install_t 00123 install() 00124 { 00125 PL_register_foreign("getPlaneClustersROS", 1, (void *)pl_getPlaneClustersROS, 0); 00126 } 00127 }