$search
00001 /* 00002 * Copyright (c) 2009, U. Klank klank@in.tum.de 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include <ros/ros.h> 00031 #include <vision_srvs/srvjlo.h> 00032 #include <stdio.h> 00033 00034 using namespace vision_srvs; 00035 00036 00037 #define JLO_IDQUERY "idquery" 00038 #define JLO_FRAMEQUERY "framequery" 00039 #define JLO_DELETE "del" 00040 #define JLO_UPDATE "update" 00041 #define ID_WORLD 1 00042 00043 int main(int argc, char* argv[]) 00044 { 00045 ros::init(argc, argv, "testjlo") ; 00046 srvjlo msg; 00047 00048 msg.request.command = JLO_UPDATE; 00049 if(argc > 2) 00050 msg.request.query.parent_id = atoi(argv[2]); 00051 else 00052 msg.request.query.parent_id = 1; 00053 if(argc > 1) 00054 msg.request.query.id = atoi(argv[1]); 00055 else 00056 { 00057 printf("Usage: ./test_jlo ID PARENT_ID R0C0 R0C1 R0C2 R0C3 R1C0 R1C1 R1C2 R1C3 R2C0 R2C1 R2C2 R2C3 NAME\n"); 00058 exit(-1); 00059 } 00060 if(argc > 15) 00061 msg.request.query.name = argv[15]; 00062 msg.request.query.type = 0; 00063 int width = 4; 00064 for(int r = 0; r < width; r++) 00065 { 00066 for(int c = 0; c < width; c++) 00067 { 00068 if(r == c) 00069 msg.request.query.pose[r * width + c] = 1; 00070 else 00071 msg.request.query.pose[r * width + c] = 0; 00072 } 00073 } 00074 msg.request.query.type = 0; 00075 /* msg.request.query.pose[3] = 0.0; 00076 msg.request.query.pose[7] = 0.0; 00077 msg.request.query.pose[11] = 0.4;*/ 00078 00079 00080 /*-0.874767 0.480757 -0.060465 0.050978 00081 -0.296898 -0.433193 0.850997 0.188964 00082 0.382929 0.762375 0.521679 0.777142 00083 0.000000 0.000000 0.000000 1.000000*/ 00084 if(argc < 15) 00085 { 00086 msg.request.query.pose[0] = 0.874767; 00087 msg.request.query.pose[1] = 0.480757; 00088 msg.request.query.pose[2] = 0.060465; 00089 msg.request.query.pose[3] = 0.050978; 00090 msg.request.query.pose[4] = 0.296898; 00091 msg.request.query.pose[5] = -0.433193; 00092 msg.request.query.pose[6] = -0.850997; 00093 msg.request.query.pose[7] = 0.188964; 00094 msg.request.query.pose[8] = -0.382929; 00095 msg.request.query.pose[9] = 0.762375; 00096 msg.request.query.pose[10] = -0.521679; 00097 msg.request.query.pose[11] = 0.777142; 00098 } 00099 else 00100 { 00101 int i = 0; 00102 msg.request.query.pose[i] = atof(argv[i + 3]); 00103 i++; //1 00104 msg.request.query.pose[i] = atof(argv[i + 3]); 00105 i++; //2 00106 msg.request.query.pose[i] = atof(argv[i + 3]); 00107 i++; //3 00108 msg.request.query.pose[i] = atof(argv[i + 3]); 00109 i++; //4 00110 msg.request.query.pose[i] = atof(argv[i + 3]); 00111 i++; //5 00112 msg.request.query.pose[i] = atof(argv[i + 3]); 00113 i++; //6 00114 msg.request.query.pose[i] = atof(argv[i + 3]); 00115 i++; //7 00116 msg.request.query.pose[i] = atof(argv[i + 3]); 00117 i++; //8 00118 msg.request.query.pose[i] = atof(argv[i + 3]); 00119 i++; //9 00120 msg.request.query.pose[i] = atof(argv[i + 3]); 00121 i++; //10 00122 msg.request.query.pose[i] = atof(argv[i + 3]); 00123 i++; //11 00124 msg.request.query.pose[i] = atof(argv[i + 3]); 00125 } 00126 00127 printf("Showing Query with PosId %d with parent %d:\n", (int)msg.request.query.id, (int)msg.request.query.parent_id); 00128 00129 for(int r = 0; r < width; r++) 00130 { 00131 for(int c = 0; c < width; c++) 00132 { 00133 printf( "%f ", msg.request.query.pose[r * width + c]); 00134 } 00135 printf("\n"); 00136 } 00137 00138 width = 6; 00139 for(int r = 0; r < width; r++) 00140 { 00141 for(int c = 0; c < width; c++) 00142 { 00143 if(r == c) 00144 { 00145 if(r == 0) 00146 { 00147 msg.request.query.cov[r * width + c] = 0.2; 00148 } 00149 else 00150 msg.request.query.cov[r * width + c] = 0.10; 00151 } 00152 else 00153 msg.request.query.cov[r * width + c] = 0; 00154 } 00155 } 00156 00157 /*msg.request.command = JLO_IDQUERY; 00158 if(argc > 2) 00159 msg.request.query.parent_id = atoi(argv[2]); 00160 if(argc > 1) 00161 msg.request.query.id = atoi(argv[1]); 00162 else msg.request.query.id = ID_WORLD;*/ 00163 ros::NodeHandle n; 00164 ros::ServiceClient client = n.serviceClient<srvjlo>("/located_object", true); 00165 if (!client.call(msg)) 00166 { 00167 printf("Error in ROSjloComm: Update of pose information not psossible!\n"); 00168 return NULL; 00169 } 00170 else if (msg.response.error.length() > 0) 00171 { 00172 printf("Error from jlo: %s!\n", msg.response.error.c_str()); 00173 } 00174 int width2 = 4; 00175 printf("Showing PosId %d with parent %d:\n", (int)msg.response.answer.id, (int)msg.response.answer.parent_id); 00176 00177 for(int r = 0; r < width2; r++) 00178 { 00179 for(int c = 0; c < width2; c++) 00180 { 00181 printf( "%f ", msg.response.answer.pose[r * width2 + c]); 00182 00183 } 00184 printf("\n"); 00185 } 00186 printf("Type: %d\n", msg.response.answer.type); 00187 00188 return 0; 00189 }