RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
test_armor.cpp
Go to the documentation of this file.
1 
2 
18 #include "ros/ros.h"
20 
21 #include "armor_msgs/ArmorDirective.h"
22 #include "armor_msgs/ArmorDirectiveList.h"
23 #include "armor_msgs/ArmorDirectiveReq.h"
24 #include "armor_msgs/ArmorDirectiveRes.h"
25 #include "armor_msgs/QueryItem.h"
26 
27 #include <iostream>
28 #include <fstream>
29 #include <string>
30 #include <vector>
31 
32 #define ONTOLOGY_PARAM "cluedo_path_owlfile"
33 #define SERVICE_ARMOR_SINGLE_REQUEST "/armor_interface_srv"
34 #define SERVICE_ARMOR_MULTIPLE_REQUESTS "/armor_interface_serialized_srv"
35 #define ARMOR_CLIENT_NAME "robocluedo"
36 #define ARMOR_REFERENCE_NAME "cluedo_ontology"
37 #define ARMOR_CMD_LOAD "LOAD"
38 #define ARMOR_TIMEOUT 5.00
39 
40 #define OUTLABEL "[test_armor] "
41 #define OUTLOG std::cout << OUTLABEL << " "
42 #define OUTERR OUTLOG << "ERROR: "
43 #define LOGSQUARE( str ) "[" << str << "] "
44 #define SS( this_string ) std::string( this_string )
45 #define SSS( this_thing ) std::to_string( this_thing )
46 
47 // check if a given file exists
48 bool fileExist( std::string path )
49 {
50  return (std::ifstream(path)).good();
51 }
52 
53 // get args to fill in the armor message
54 std::vector<std::string> armorGetArgs(
55  std::string arg1,
56  std::string arg2 = "",
57  std::string arg3 = "",
58  std::string arg4 = "",
59  std::string arg5 = ""
60 )
61 {
62  std::vector<std::string> to_return;
63  to_return.push_back( arg1 );
64  to_return.push_back( arg2 );
65  to_return.push_back( arg3 );
66  to_return.push_back( arg4 );
67  to_return.push_back( arg5 );
68 
69  return to_return;
70 }
71 
72 // armor call
73 armor_msgs::ArmorDirective armorGetRequest(
74  std::string client,
75  std::string reference,
76  std::string command,
77  std::string first_spec = "",
78  std::string second_spec = "",
79  std::vector<std::string> args = std::vector<std::string>(5, "")
80  )
81 {
82  armor_msgs::ArmorDirective adsrv;
83  armor_msgs::ArmorDirectiveReq ad;
84 
85  ad.client_name = client;
86  ad.reference_name = reference;
87 
88  ad.command = command;
89  ad.primary_command_spec = first_spec;
90  ad.secondary_command_spec = second_spec;
91  ad.args = args;
92 
93  adsrv.request.armor_request = ad;
94 
95  return adsrv;
96 }
97 
98 // print the armor request
99 void armorPrintRequest( armor_msgs::ArmorDirective& d )
100 {
101  std::string str = SS(OUTLABEL) + SS("Print Request: \n");
102  armor_msgs::ArmorDirectiveReq r = d.request.armor_request;
103 
104  str += SS("\tclient_name : ") + SS( r.client_name ) + SS("\n");
105  str += SS("\treference_name : ") + SS( r.reference_name ) + SS("\n");
106  str += SS("\tcommand : ") + SS( r.command ) + SS("\n");
107  str += SS("\tprimary_command_spec : ") + SS( r.primary_command_spec ) + SS("\n");
108  str += SS("\tsecondary_command_spec : ") + SS( r.secondary_command_spec ) + SS("\n");
109 
110  str += SS("\targs : [");
111  for( std::string arg : r.args )
112  str += SS( arg ) + SS(" ");
113  str += SS( "]" );
114 
115  str += SS( "\n\t---" );
116 
117  ROS_INFO_STREAM( str );
118 }
119 
120 // print the whole armor response
121 void armorPrintResponse( armor_msgs::ArmorDirective& d )
122 {
123  std::string str = SS(OUTLABEL) + SS("Print Response: \n");
124  armor_msgs::ArmorDirectiveRes r = d.response.armor_response;
125 
126  str += SS("\tsuccess : ") + ( r.success ? SS("true") : SS("false") ) + SS("\n");
127  str += SS("\ttimeout : ") + ( r.timeout ? SS("true") : SS("false") ) + SS("\n");
128  str += SS("\texit_code : ") + SSS(r.exit_code) + SS("\n");
129  str += SS("\terror_description : ") + SS(r.error_description) + SS("\n");
130  str += SS("\tis_consistent : ") + ( r.is_consistent ? SS("true") : SS("false") ) + SS("\n");
131 
132  str += SS("\tqueried_objects :\n");
133  for( std::string s : r.queried_objects )
134  str += SS("\t-\t") + s + SS("\n");
135 
136  str += SS("\tsparql_queried_objects : \n");
137  for( armor_msgs::QueryItem s : r.sparql_queried_objects )
138  str += SS("\t-\t") + SS("key: ") + SS( s.key ) + SS( " | value: " ) + SS( s.value ) + SS("\n");
139 
140  str += SS( "\t---" );
141 
142  ROS_INFO_STREAM( str );
143 }
144 
145 // call to aRMOR service
146 bool armorCallService( ros::ServiceClient& armorClient, armor_msgs::ArmorDirective& armorsrvdata )
147 {
148  if( armorClient.call( armorsrvdata ) )
149  {
150  /*
151  if( armorsrvdata.response.armor_response.success )
152  {
153  return true;
154  }
155  else
156  return false;
157  */
158  return true;
159  }
160  else
161  return false;
162 }
163 
164 /*
165  * nuovo indvidual:
166  * ADD IND CLASS [ individual, class ]
167  *
168  * nuova proprietà:
169  * ADD OBJECTPROP IND [ prop, domain, img ]
170  *
171  * caricamento da file:
172  * LOAD FILE [ path ]
173  *
174  */
175 void armorTestSession( ros::ServiceClient& cl, std::string path )
176 {
177  //armor_msgs::ArmorDirective adsrv;
178  //ROS_INFO_STREAM( OUTLABEL << "client_name" << LOGSQUARE( ARMOR_CLIENT_NAME ) << "reference_name" << LOGSQUARE( ARMOR_REFERENCE_NAME ) );
179 
180  std::vector<armor_msgs::ArmorDirective> directives;
181 
182  // caricamento dell'ontology da file
183  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "LOAD", "FILE", "", armorGetArgs( path, "http://www.emarolab.it/cluedo-ontology", "false", "PELLET", "true" ) ) );
184 
185  // ipotesi consistente: where:Stadium, who:Jim, what:Gun
186  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "IND", "CLASS", armorGetArgs( "Jim", "PERSON" ) ) );
187  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "OBJECTPROP", "IND", armorGetArgs( "who", "HP3", "Jim" ) ) );
188  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "IND", "CLASS", armorGetArgs( "Gun", "WEAPON" ) ) );
189  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "OBJECTPROP", "IND", armorGetArgs( "what", "HP3", "Gun" ) ) );
190  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "IND", "CLASS", armorGetArgs( "Stadium", "PLACE" ) ) );
191  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "OBJECTPROP", "IND", armorGetArgs( "where", "HP3", "Stadium" ) ) );
192  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "REASON", "", "", armorGetArgs( "" ) ) );
193 
194  // l'ipotesi diventa inconsistente quando viene aggiunto where:Lounge E SI FA DISJOINT con l'altro luogo
195  // (a quanto pare quando si aggiunge l'etichetta, aRMOR pensa sia la stessa cosa aggiunta prima ... perchè?)
196  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "IND", "CLASS", armorGetArgs( "Lounge", "PLACE" ) ) );
197  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "DISJOINT", "IND", "", armorGetArgs( "Lounge", "Stadium" ) ) );
198  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "ADD", "OBJECTPROP", "IND", armorGetArgs( "where", "HP3", "Lounge" ) ) );
199  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "REASON", "", "", armorGetArgs( "" ) ) );
200  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "SAVE", "INFERENCE", "", armorGetArgs( "/root/Desktop/ROBOCLUEDO_ONTOLOGY.owl" ) ) );
201  // directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "", "", "", armorGetArgs( "", "", "", "", "" ) ) );
202 
203  /*
204  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "QUERY", "IND", "CLASS", armorGetArgs( "COMPLETED" ) ) );
205  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "QUERY", "IND", "CLASS", armorGetArgs( "INCONSISTENT" ) ) );
206  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "QUERY", "OBJECTPROP", "IND", armorGetArgs( "who", "HP0" ) ) );
207  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "QUERY", "OBJECTPROP", "IND", armorGetArgs( "where", "HP0" ) ) );
208  directives.push_back( armorGetRequest( ARMOR_CLIENT_NAME, ARMOR_REFERENCE_NAME, "QUERY", "OBJECTPROP", "IND", armorGetArgs( "what", "HP0" ) ) );
209  */
210 
211  for( auto adsrv = directives.begin(); adsrv != directives.end(); ++adsrv )
212  {
213  armorPrintRequest( *adsrv );
214  armorCallService( cl, *adsrv );
215  armorPrintResponse( *adsrv );
216  }
217 }
218 
219 // test section
220 int main( int argc, char* argv[] )
221 {
222  ros::init( argc, argv, "test_armor" );
223  ros::NodeHandle nh;
224 
225  // path of the ontology file from parameter server
226  std::string ontology_file_path;
227  if( !ros::param::has( ONTOLOGY_PARAM ) )
228  {
229  ROS_INFO_STREAM( OUTLABEL << "ERROR: parameter '" << ONTOLOGY_PARAM << "' not defined." );
230  return 0;
231  }
232  ros::param::get( ONTOLOGY_PARAM, ontology_file_path );
233  if( !fileExist( ontology_file_path ) )
234  {
235  ROS_INFO_STREAM( OUTLABEL << "ERROR: the file '" << ONTOLOGY_PARAM << "' doesn't exist." );
236  return 0;
237  }
238  ROS_INFO_STREAM( OUTLABEL << "Ontology found! " << LOGSQUARE( ontology_file_path ) );
239 
240  // request for aRMOR service single request
241  ROS_INFO_STREAM( OUTLABEL << "Requiring client " << LOGSQUARE( SERVICE_ARMOR_SINGLE_REQUEST ) << "..." );
242  ros::ServiceClient cl_single = nh.serviceClient<armor_msgs::ArmorDirective>( SERVICE_ARMOR_SINGLE_REQUEST );
243  if( !cl_single.waitForExistence( ros::Duration( ARMOR_TIMEOUT ) ) )
244  {
245  ROS_INFO_STREAM( OUTLABEL << "ERROR: unable to contact the server - timeout expired (" << ARMOR_TIMEOUT << "s) " );
246  return 0;
247  }
248  ROS_INFO_STREAM( OUTLABEL << "Requiring client " << LOGSQUARE( SERVICE_ARMOR_SINGLE_REQUEST ) << "... OK" );
249 
250  // request for aRMOR service multiple requests
251  ROS_INFO_STREAM( OUTLABEL << "Requiring client " << LOGSQUARE( SERVICE_ARMOR_MULTIPLE_REQUESTS ) << "..." );
252  ros::ServiceClient cl_multi = nh.serviceClient<armor_msgs::ArmorDirectiveList>( SERVICE_ARMOR_MULTIPLE_REQUESTS );
253  if( !cl_single.waitForExistence( ros::Duration( ARMOR_TIMEOUT ) ) )
254  {
255  ROS_INFO_STREAM( OUTLABEL << "ERROR: unable to contact the server - timeout expired (" << ARMOR_TIMEOUT << "s) " );
256  return 0;
257  }
258  ROS_INFO_STREAM( OUTLABEL << "Requiring client " << LOGSQUARE( SERVICE_ARMOR_MULTIPLE_REQUESTS ) << "... OK" );
259 
260  // start testing phase
261  armorTestSession( cl_single, ontology_file_path );
262 
263  ROS_INFO_STREAM( OUTLABEL << "closing..." );
264  return 0;
265 }
armorPrintRequest
void armorPrintRequest(armor_msgs::ArmorDirective &d)
Definition: test_armor.cpp:99
ONTOLOGY_PARAM
#define ONTOLOGY_PARAM
Definition: test_armor.cpp:32
SSS
#define SSS(this_thing)
Definition: test_armor.cpp:45
SERVICE_ARMOR_MULTIPLE_REQUESTS
#define SERVICE_ARMOR_MULTIPLE_REQUESTS
Definition: test_armor.cpp:34
ARMOR_TIMEOUT
#define ARMOR_TIMEOUT
Definition: test_armor.cpp:38
armorPrintResponse
void armorPrintResponse(armor_msgs::ArmorDirective &d)
Definition: test_armor.cpp:121
LOGSQUARE
#define LOGSQUARE(str)
Definition: test_armor.cpp:43
OUTLABEL
#define OUTLABEL
Definition: test_armor.cpp:40
ARMOR_CLIENT_NAME
#define ARMOR_CLIENT_NAME
Definition: test_armor.cpp:35
main
int main(int argc, char *argv[])
Definition: test_armor.cpp:220
SERVICE_ARMOR_SINGLE_REQUEST
#define SERVICE_ARMOR_SINGLE_REQUEST
Definition: test_armor.cpp:33
armorGetRequest
armor_msgs::ArmorDirective armorGetRequest(std::string client, std::string reference, std::string command, std::string first_spec="", std::string second_spec="", std::vector< std::string > args=std::vector< std::string >(5, ""))
Definition: test_armor.cpp:73
armorGetArgs
std::vector< std::string > armorGetArgs(std::string arg1, std::string arg2="", std::string arg3="", std::string arg4="", std::string arg5="")
Definition: test_armor.cpp:54
fileExist
bool fileExist(std::string path)
Definition: test_armor.cpp:48
armorCallService
bool armorCallService(ros::ServiceClient &armorClient, armor_msgs::ArmorDirective &armorsrvdata)
Definition: test_armor.cpp:146
ARMOR_REFERENCE_NAME
#define ARMOR_REFERENCE_NAME
Definition: test_armor.cpp:36
armorTestSession
void armorTestSession(ros::ServiceClient &cl, std::string path)
Definition: test_armor.cpp:175
SS
#define SS(this_string)
Definition: test_armor.cpp:44
armor_tools.h
A minimal C++ client for aRMOR.