RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
armor_tools.cpp
Go to the documentation of this file.
1 
2 
14 
15 
16 
17 // constructor with three arguments
19  std::string client,
20  std::string reference,
21  bool dbmode
22  ):
23  ClientName( client ),
24  ReferenceName( reference ),
25  DebugMode( dbmode )
26 {
27  // stub init of the last request
28  LastReq.client_name = client;
29  LastReq.reference_name = reference;
30  LastReq.command = "";
31  LastReq.primary_command_spec = "";
32  LastReq.secondary_command_spec = "";
33  // LastReq.args = std::vector<std::string>( 5, "" );
34 
35  // stub init of the last response
36  LastRes.success = true;
37  LastRes.timeout = false;
38  LastRes.exit_code = 0;
39  LastRes.error_description = "";
40  LastRes.is_consistent = true;
41  // LastRes.queried_objects = std::vector<std::string>( );
42  // LastRes.sparql_queried_objects = std::vector<armor_msgs::QueryItem>( );
43 }
44 
45 
46 
47 // constructor with one argument
48 ArmorTools::ArmorTools( bool dbmode ):
49  ClientName( ARMOR_DEFAULT_CLIENT ),
50  ReferenceName( ARMOR_DEFAULT_REFERENCE ),
51  DebugMode( dbmode )
52 {
53  // stub init of the last request
54  LastReq.client_name = ClientName;
55  LastReq.reference_name = ReferenceName;
56  LastReq.command = "";
57  LastReq.primary_command_spec = "";
58  LastReq.secondary_command_spec = "";
59  // LastReq.args = std::vector<std::string>( 5, "" );
60 
61  // stub init of the last response
62  LastRes.success = true;
63  LastRes.timeout = false;
64  LastRes.exit_code = 0;
65  LastRes.error_description = "";
66  LastRes.is_consistent = true;
67  // LastRes.queried_objects = std::vector<std::string>( );
68  // LastRes.sparql_queried_objects = std::vector<armor_msgs::QueryItem>( );
69 }
70 
71 
72 
73 // destructor
75 {
76  // ...
77 }
78 
79 
80 
81 // fill in the request
82 armor_msgs::ArmorDirective ArmorTools::GetRequest(
83  std::string command,
84  std::string first_spec,
85  std::string second_spec,
86  std::string arg1,
87  std::string arg2,
88  std::string arg3,
89  std::string arg4,
90  std::string arg5
91  )
92 {
93  armor_msgs::ArmorDirective adsrv;
94  armor_msgs::ArmorDirectiveReq ad;
95 
96  ad.client_name = this->ClientName;
97  ad.reference_name = this->ReferenceName;
98 
99  ad.command = command;
100  ad.primary_command_spec = first_spec;
101  ad.secondary_command_spec = second_spec;
102 
103  ad.args = std::vector<std::string>();
104  ad.args.push_back( arg1 );
105  ad.args.push_back( arg2 );
106  ad.args.push_back( arg3 );
107  ad.args.push_back( arg4 );
108  ad.args.push_back( arg5 );
109 
110  adsrv.request.armor_request = ad;
111 
112  return adsrv;
113 }
114 
115 
116 
117 // call aRMOR
118 bool ArmorTools::CallArmor( armor_msgs::ArmorDirective& data )
119 {
120  // if there is no server, don't call it
121  if( !this->ArmorSrv.exists() )
122  {
123  ARMOR_ERR( "no service found!" );
124  return false;
125  }
126 
127  // save the received request
128  this->LastReq = data.request.armor_request;
129 
130  // try to call it
131  if( !this->ArmorSrv.call( data ) )
132  {
133  ARMOR_ERR( "unable to call ArmorService" << LOGSQUARE( ARMOR_SERVICE_SINGLE_REQUEST ) );
134  return false;
135  }
136 
137  // save the last received response
138  this->LastRes = data.response.armor_response;
139 
140  return true;
141 }
142 
143 
144 
145 // load the ontology from file
147  std::string path,
148  std::string uri,
149  bool manipulationFlag,
150  std::string reasoner,
151  bool buffered_reasoner
152  )
153 {
154  // if there is no server, don't call it
155  if( !this->ArmorSrv.exists() )
156  {
157  ARMOR_ERR( "no service found!" );
158  return false;
159  }
160 
161  // check if the file exists
162  if( !this->FileExist( path ) )
163  {
164  ARMOR_ERR( "OWL file not found. " << LOGSQUARE( path ) );
165  return false;
166  }
167 
168  // prepare the command load
169  armor_msgs::ArmorDirective load_cmd = GetRequest(
170  "LOAD", "FILE", "",
171  path, uri, BOOL_TO_CSTR( manipulationFlag ), reasoner, BOOL_TO_CSTR( buffered_reasoner )
172  );
173 
174  // call the service
175  if( !CallArmor( load_cmd ) )
176  {
177  ARMOR_ERR( "unable to call the service!" );
178  return false;
179  }
180 
181  return (IsLoadedInterface = load_cmd.response.armor_response.success);
182 }
183 
184 
185 
186 // connection to the service aRMOR
187 bool ArmorTools::Connect( float timeout )
188 {
189  // check if the service exists
190  if( this->ArmorSrv.exists() )
191  {
192  ARMOR_INFO( "service already connected!" );
193  return false;
194  }
195 
196  // connect to the service
197  ros::NodeHandle nh;
198  ARMOR_INFO( "Requiring client " << LOGSQUARE( ARMOR_SERVICE_SINGLE_REQUEST ) << "..." );
199  this->ArmorSrv = nh.serviceClient<armor_msgs::ArmorDirective>( ARMOR_SERVICE_SINGLE_REQUEST );
200  if( !this->ArmorSrv.waitForExistence( ros::Duration( timeout ) ) )
201  {
202  ARMOR_ERR( "ERROR: unable to contact the server - timeout expired (" << timeout << "s) " );
203  return false;
204  }
205  ARMOR_INFO( "-> OK" );
206 
207  return true;
208 }
209 
210 
211 
212 // connect and load from file
214  std::string path,
215  std::string uri,
216  bool manipulationFlag,
217  std::string reasoner,
218  bool buffered_reasoner
219  )
220 {
221  if ( Connect( ) &&
222  LoadOntology( path, uri, manipulationFlag, reasoner, buffered_reasoner ) )
223  return true;
224  else
225  return false;
226 }
227 
228 
229 
230 // save the ontology on file
231 bool ArmorTools::SaveOntology( std::string path )
232 {
233  ARMOR_CHECK_INTERFACE( false );
234 
235  // try to call the service
236  auto srvdata = GetRequest( "SAVE", "INFERENCE", "", path );
237  if( !CallArmor( srvdata ) )
238  return false;
239 
240  return srvdata.response.armor_response.success;
241 }
242 
243 
244 
245 // update the ontology
247 {
248  ARMOR_CHECK_INTERFACE( false );
249 
250  auto srvdata = GetRequest( "REASON" );
251  if( !CallArmor( srvdata ) )
252  return false;
253 
254  return ARMOR_RES( srvdata ).success;
255 }
256 
257 
258 
259 // print a request to the screen
260 void ArmorTools::PrintRequest( armor_msgs::ArmorDirective& d )
261 {
262  std::string str = SS(" Print Request: \n");
263  armor_msgs::ArmorDirectiveReq r = d.request.armor_request;
264 
265  str += SS("\tclient_name : ") + SS( r.client_name ) + SS("\n");
266  str += SS("\treference_name : ") + SS( r.reference_name ) + SS("\n");
267  str += SS("\tcommand : ") + SS( r.command ) + SS("\n");
268  str += SS("\tprimary_command_spec : ") + SS( r.primary_command_spec ) + SS("\n");
269  str += SS("\tsecondary_command_spec : ") + SS( r.secondary_command_spec ) + SS("\n");
270 
271  str += SS("\targs : [");
272  for( std::string arg : r.args )
273  str += SS( arg ) + SS(" ");
274  str += SS( "]" );
275 
276  str += SS( "\n\t---" );
277 
278  ROS_INFO_STREAM( str );
279 }
280 
281 
282 
283 // print a response to the screen
284 void ArmorTools::PrintResponse( armor_msgs::ArmorDirective& d )
285 {
286  std::string str = SS(" Print Response: \n");
287  armor_msgs::ArmorDirectiveRes r = d.response.armor_response;
288 
289  str += SS("\tsuccess : ") + ( r.success ? SS("true") : SS("false") ) + SS("\n");
290  str += SS("\ttimeout : ") + ( r.timeout ? SS("true") : SS("false") ) + SS("\n");
291  str += SS("\texit_code : ") + SSS(r.exit_code) + SS("\n");
292  str += SS("\terror_description : ") + SS(r.error_description) + SS("\n");
293  str += SS("\tis_consistent : ") + ( r.is_consistent ? SS("true") : SS("false") ) + SS("\n");
294 
295  str += SS("\tqueried_objects :\n");
296  for( std::string s : r.queried_objects )
297  str += SS("\t-\t") + s + SS("\n");
298 
299  str += SS("\tsparql_queried_objects : \n");
300  for( armor_msgs::QueryItem s : r.sparql_queried_objects )
301  str += SS("\t-\t") + SS("key: ") + SS( s.key ) + SS( " | value: " ) + SS( s.value ) + SS("\n");
302 
303  str += SS( "\t---" );
304 
305  ROS_INFO_STREAM( str );
306 }
307 
308 
309 
310 // toggle debug mode
312 {
313  this->DebugMode = !this->DebugMode;
314 }
315 
316 
317 
318 // get the error code referred from the last response
320 {
321  return this->LastRes.exit_code;
322 }
323 
324 
325 
326 // get the error description from the last response
328 {
329  return SS( this->LastRes.error_description );
330 }
331 
332 
333 
334 // last flag 'success'
336 {
337  return this->LastRes.success;
338 }
339 
340 
341 
342 // check if the ontology was loaded
344 {
345  return IsLoadedInterface;
346 }
347 
348 
349 
350 // test the interface
352 {
353  ARMOR_CHECK_INTERFACE( false );
354  return true;
355 }
356 
357 
358 
359 // fill in the command and send it
361  std::string command,
362  std::string first_spec,
363  std::string second_spec,
364  std::string arg1,
365  std::string arg2,
366  std::string arg3,
367  std::string arg4,
368  std::string arg5,
369  bool printRequest
370  )
371 {
372  ARMOR_CHECK_INTERFACE( false );
373 
374  // build the message to send
375  auto srvdata = GetRequest( command, first_spec, second_spec, arg1, arg2, arg3, arg4, arg5 );
376  if( printRequest ) this->PrintRequest( srvdata );
377 
378  // and send it
379  return CallArmor( srvdata );
380 }
381 
382 
383 
384 // get a reference to the last response
385 armor_msgs::ArmorDirectiveRes& ArmorTools::GetLastRes( )
386 {
387  armor_msgs::ArmorDirectiveRes& res = this->LastRes;
388  return res;
389 }
390 
391 
392 
393 // get a reference to the last request
394 armor_msgs::ArmorDirectiveReq& ArmorTools::GetLastReq( )
395 {
396  armor_msgs::ArmorDirectiveReq& req = this->LastReq;
397  return req;
398 }
399 
400 
401 
402 // print to the screen the last response
404 {
405  armor_msgs::ArmorDirective armordata;
406  armordata.response.armor_response = this->LastRes;
407  PrintResponse( armordata );
408 }
409 
410 
411 
412 // print to the screen the last request
414 {
415  armor_msgs::ArmorDirective armordata;
416  armordata.request.armor_request = this->LastReq;
417  PrintRequest( armordata );
418 }
419 
420 
421 
422 // check if a file exists, given its path
423 bool ArmorTools::FileExist( std::string path )
424 {
425  return (std::ifstream(path)).good();
426 }
ARMOR_DEFAULT_CLIENT
#define ARMOR_DEFAULT_CLIENT
Definition: armor_tools.h:31
ArmorTools::ConnectAndLoad
bool ConnectAndLoad(std::string path, std::string uri=ARMOR_DEFAULT_URI, bool manipulationFlag=true, std::string reasoner=ARMOR_DEFAULT_REASONER, bool buffered_reasoner=true)
connect to the server and load the ontology from file.
Definition: armor_tools.cpp:213
ArmorTools::PrintLastRes
void PrintLastRes()
print the last response
Definition: armor_tools.cpp:403
SS
#define SS(this_string)
Definition: armor_tools.h:46
ArmorTools::PrintResponse
void PrintResponse(armor_msgs::ArmorDirective &d)
print the response to the screen.
Definition: armor_tools.cpp:284
ArmorTools::GetLastErrorDescription
std::string GetLastErrorDescription()
last err description
Definition: armor_tools.cpp:327
ArmorTools::GetLastReq
armor_msgs::ArmorDirectiveReq & GetLastReq()
get a reference to the last request
Definition: armor_tools.cpp:394
ARMOR_ERR
#define ARMOR_ERR(msg)
Definition: armor_tools.h:41
ArmorTools::~ArmorTools
~ArmorTools()
class destructor (empty)
Definition: armor_tools.cpp:74
ARMOR_INFO
#define ARMOR_INFO(msg)
Definition: armor_tools.h:40
ArmorTools::PrintRequest
void PrintRequest(armor_msgs::ArmorDirective &d)
print a request to the screen.
Definition: armor_tools.cpp:260
ArmorTools::SwitchDebugMode
void SwitchDebugMode()
toggle the debug mode
Definition: armor_tools.cpp:311
ArmorTools::GetLastRes
armor_msgs::ArmorDirectiveRes & GetLastRes()
get a reference to the last response
Definition: armor_tools.cpp:385
ArmorTools::LoadedOntology
bool LoadedOntology()
check if the ontology was loaded or not
Definition: armor_tools.cpp:343
ARMOR_CHECK_INTERFACE
#define ARMOR_CHECK_INTERFACE(returnval)
Definition: armor_tools.h:42
ARMOR_RES
#define ARMOR_RES(msg)
Definition: armor_tools.h:43
ArmorTools::ArmorTools
ArmorTools(std::string client=ARMOR_DEFAULT_CLIENT, std::string reference=ARMOR_DEFAULT_REFERENCE, bool dbmode=false)
Class Constructor, 3 arguments.
Definition: armor_tools.cpp:18
ArmorTools::GetRequest
armor_msgs::ArmorDirective GetRequest(std::string command, std::string first_spec="", std::string second_spec="", std::string arg1="", std::string arg2="", std::string arg3="", std::string arg4="", std::string arg5="")
quick generation of an aRMOR request
Definition: armor_tools.cpp:82
ARMOR_SERVICE_SINGLE_REQUEST
#define ARMOR_SERVICE_SINGLE_REQUEST
Definition: armor_tools.h:36
LOGSQUARE
#define LOGSQUARE(str)
Definition: armor_tools.h:49
ArmorTools::LoadOntology
bool LoadOntology(std::string path, std::string uri=ARMOR_DEFAULT_URI, bool manipulationFlag=true, std::string reasoner=ARMOR_DEFAULT_REASONER, bool buffered_reasoner=true)
load the ontology from file.
Definition: armor_tools.cpp:146
ArmorTools::TestInterface
bool TestInterface()
check the status of the interface
Definition: armor_tools.cpp:351
SSS
#define SSS(this_thing)
Definition: armor_tools.h:47
ArmorTools::UpdateOntology
bool UpdateOntology()
send the command REASON
Definition: armor_tools.cpp:246
ArmorTools::Success
bool Success()
check the 'success' flag referred to the last aRMOR call
Definition: armor_tools.cpp:335
ArmorTools::Connect
bool Connect(float timeout=ARMOR_DEFAULT_TIMEOUT)
open a connection with the aRMOR service.
Definition: armor_tools.cpp:187
ArmorTools::SendCommand
bool SendCommand(std::string command, std::string first_spec="", std::string second_spec="", std::string arg1="", std::string arg2="", std::string arg3="", std::string arg4="", std::string arg5="", bool printRequest=false)
fill in a command and send it to aRMOR
Definition: armor_tools.cpp:360
ArmorTools::CallArmor
bool CallArmor(armor_msgs::ArmorDirective &data)
send a command to the aRMOR service.
Definition: armor_tools.cpp:118
ArmorTools::DebugMode
bool DebugMode
debug mode enabled or not
Definition: armor_tools.h:440
ArmorTools::PrintLastReq
void PrintLastReq()
print the last request
Definition: armor_tools.cpp:413
ArmorTools::SaveOntology
bool SaveOntology(std::string path)
save the ontology on file
Definition: armor_tools.cpp:231
ARMOR_DEFAULT_REFERENCE
#define ARMOR_DEFAULT_REFERENCE
Definition: armor_tools.h:32
armor_tools.h
A minimal C++ client for aRMOR.
ArmorTools::GetLastErrorCode
int GetLastErrorCode()
err code referred to the last call
Definition: armor_tools.cpp:319
BOOL_TO_CSTR
#define BOOL_TO_CSTR(booleanvalue)
Definition: armor_tools.h:48