RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
armor_tools.h
Go to the documentation of this file.
1 
2 
14 #ifndef __H_ARMOR_TOOLS_H__
15 #define __H_ARMOR_TOOLS_H__
16 
17 #include "ros/ros.h"
18 #include "armor_msgs/QueryItem.h"
19 #include "armor_msgs/ArmorDirective.h"
20 #include "armor_msgs/ArmorDirectiveReq.h"
21 #include "armor_msgs/ArmorDirectiveRes.h"
22 
23 #include <iostream>
24 #include <vector>
25 #include <map>
26 #include <string>
27 #include <fstream>
28 
29 #define ARMOR_DEFAULT_URI "http://www.emarolab.it/cluedo-ontology"
30 #define ARMOR_DEFAULT_REASONER "PELLET"
31 #define ARMOR_DEFAULT_CLIENT "armor_client"
32 #define ARMOR_DEFAULT_REFERENCE "cluedo"
33 #define ARMOR_DEFAULT_TIMEOUT 5.00
34 #define ARMOR_DEFAULT_DEBUGMODE true
35 
36 #define ARMOR_SERVICE_SINGLE_REQUEST "/armor_interface_srv"
37 #define ARMOR_SERVICE_MULTIPLE_REQUESTS "/armor_interface_serialized_srv"
38 
39 #define ARMOR_CLASS_LABEL "[armor_tools]"
40 #define ARMOR_INFO( msg ) if( this->DebugMode ) ROS_INFO_STREAM( ARMOR_CLASS_LABEL << " " << msg )
41 #define ARMOR_ERR( msg ) if( this->DebugMode ) ROS_WARN_STREAM( ARMOR_CLASS_LABEL << " ERROR: " << msg )
42 #define ARMOR_CHECK_INTERFACE( returnval ) if( !IsLoadedInterface || !ArmorSrv.exists( ) ) { ARMOR_ERR( "bad interface!" ); return returnval; }
43 #define ARMOR_RES( msg ) msg.response.armor_response
44 #define ARMOR_RES_QUERY( msg ) msg.response.armor_response.queried_objects
45 
46 #define SS( this_string ) std::string( this_string )
47 #define SSS( this_thing ) std::to_string( this_thing )
48 #define BOOL_TO_CSTR( booleanvalue ) ( booleanvalue ? "true" : "false" )
49 #define LOGSQUARE( str ) "[" << str << "] "
50 
51 
52 
53 
54 
91 {
92 public:
93 
107  ArmorTools(
108  std::string client = ARMOR_DEFAULT_CLIENT,
109  std::string reference = ARMOR_DEFAULT_REFERENCE,
110  bool dbmode = false
111  );
112 
113 
114 
124  ArmorTools( bool dbmode );
125 
126 
128  ~ArmorTools();
129 
130 
131 
148  armor_msgs::ArmorDirective GetRequest(
149  std::string command,
150  std::string first_spec = "",
151  std::string second_spec = "",
152  std::string arg1 = "",
153  std::string arg2 = "",
154  std::string arg3 = "",
155  std::string arg4 = "",
156  std::string arg5 = ""
157  );
158 
159 
160 
176  bool CallArmor( armor_msgs::ArmorDirective& data );
177 
178 
179 
201  bool LoadOntology(
202  std::string path,
203  std::string uri = ARMOR_DEFAULT_URI,
204  bool manipulationFlag = true,
205  std::string reasoner = ARMOR_DEFAULT_REASONER,
206  bool buffered_reasoner = true
207  );
208 
209 
210 
227  bool Connect( float timeout = ARMOR_DEFAULT_TIMEOUT );
228 
229 
230 
242  bool ConnectAndLoad(
243  std::string path,
244  std::string uri = ARMOR_DEFAULT_URI,
245  bool manipulationFlag = true,
246  std::string reasoner = ARMOR_DEFAULT_REASONER,
247  bool buffered_reasoner = true
248  );
249 
250 
251 
265  bool SaveOntology( std::string path );
266 
267 
268 
284  bool UpdateOntology( );
285 
286 
287 
294  void PrintRequest( armor_msgs::ArmorDirective& d );
295 
296 
297 
304  void PrintResponse( armor_msgs::ArmorDirective& d );
305 
306 
307 
315  void SwitchDebugMode( );
316 
317 
318 
325  int GetLastErrorCode( );
326 
327 
328 
335  std::string GetLastErrorDescription( );
336 
337 
338 
351  bool Success( );
352 
353 
354 
361  bool LoadedOntology( );
362 
363 
364 
371  bool TestInterface( );
372 
373 
374 
389  bool SendCommand(
390  std::string command,
391  std::string first_spec = "",
392  std::string second_spec = "",
393  std::string arg1 = "",
394  std::string arg2 = "",
395  std::string arg3 = "",
396  std::string arg4 = "",
397  std::string arg5 = "",
398  bool printRequest = false
399  );
400 
401 
402 
409  armor_msgs::ArmorDirectiveRes& GetLastRes( );
410 
411 
412 
419  armor_msgs::ArmorDirectiveReq& GetLastReq( );
420 
421 
422 
427  void PrintLastRes( );
428 
429 
430 
435  void PrintLastReq( );
436 
437 protected:
438 
440  bool DebugMode = false;
441 
442 private:
443  // aRMOR service
444  ros::ServiceClient ArmorSrv;
445 
446  // client name
447  std::string ClientName = ARMOR_DEFAULT_CLIENT;
448 
449  // reference name
450  std::string ReferenceName = ARMOR_DEFAULT_REFERENCE;
451 
452  // uri
453  std::string uri = ARMOR_DEFAULT_URI;
454 
455  // interface loaded?
456  // l'ultimo comando load ha avuto successo?
457  bool IsLoadedInterface = false;
458 
459  // last response from the server
460  armor_msgs::ArmorDirectiveRes LastRes;
461 
462  // last request sent to the server
463  armor_msgs::ArmorDirectiveReq LastReq;
464 
465  // controlla se il dato file esiste
466  bool FileExist( std::string path );
467 };
468 
469 
470 #endif
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
ARMOR_DEFAULT_REASONER
#define ARMOR_DEFAULT_REASONER
Definition: armor_tools.h:30
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_DEFAULT_TIMEOUT
#define ARMOR_DEFAULT_TIMEOUT
Definition: armor_tools.h:33
ArmorTools::~ArmorTools
~ArmorTools()
class destructor (empty)
Definition: armor_tools.cpp:74
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
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
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
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
A minimal C++ client for aRMOR.
Definition: armor_tools.h:90
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_DEFAULT_URI
#define ARMOR_DEFAULT_URI
Definition: armor_tools.h:29
ArmorTools::GetLastErrorCode
int GetLastErrorCode()
err code referred to the last call
Definition: armor_tools.cpp:319