Go to the documentation of this file.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
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
00078 if (client.call(srv))
00079 {
00080 ROS_DEBUG("srv.response.id %ld", srv.response.id);
00081
00082 if (!PL_unify_list(l, tmp, l) ||
00083 !PL_unify_integer(tmp, srv.response.id))
00084 PL_fail;
00085
00086
00087
00088
00089
00090
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
00122 install_t
00123 install()
00124 {
00125 PL_register_foreign("getPlaneClustersROS", 1, (void *)pl_getPlaneClustersROS, 0);
00126 }
00127 }