RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
example_armor_tools_1.cpp
Go to the documentation of this file.
1 
2 
26 #include "ros/ros.h"
28 #include "armor_msgs/ArmorDirective.h"
29 #include "armor_msgs/ArmorDirectiveReq.h"
30 #include "armor_msgs/ArmorDirectiveRes.h"
31 
32 #include <iostream>
33 #include <string>
34 
35 int main( int argc, char* argv[] )
36 {
37  ros::init( argc, argv, "example_armor_tools_1" );
38  ros::NodeHandle nh;
39 
40 
41 
42 
43  // STEP 0 === CONSTRUCTOR
44 
45  // constructor with no arguments:
46  // set default client name and reference name
47  // debug mode is off
48  // infos are stored for later in the load step
49  ArmorTools armor;
50  // another way: set your client name and reference
51  ArmorTools armor2( "my_client", "my_reference" );
52  // only debug mode, with default infos
53  ArmorTools armorDBmode( true );
54 
55  // you can toggle the debug mode in any time using
56  armor.SwitchDebugMode( );
57 
58 
59 
60 
61  // STEP 1 === CONNECTION
62 
63  // the connection to the server is stored inside the class
64  // using the default timeout
65  if( !armor.Connect( ) )
66  {
67  std::cout << "connection error!" << std::endl;
68  return 0;
69  }
70  // if you want to set another timeout, use this:
71  // armor.Connect( ros::Duration( 36 ) );
72 
73 
74 
75 
76  // STEP 2 === LOAD ONTOLOGY FROM FILE
77 
78  // straightforward: use the dedicated function
79  // alternatively, you can load manually the ontology; there are several ways
80  if( !armor.LoadOntology( "/root/ontology/my_pizza_ontology.owl" ) )
81  {
82  // something went wrong...
83  }
84  // see ArmorTools::LoadOntology() for more details
85 
86  // check the calidity of the interface
87  if( !armor.TestInterface( ) )
88  {
89  // something went wrong...
90  }
91 
92 
93 
94 
95  // STEP 3 === REQUEST & CALLS
96 
97  // quickest way to call aRMOR
98  armor.SendCommand( "ADD", "IND", "CLASS", "Giampiero", "PERSON" );
99 
100  // manual aRMOR call
101  armor_msgs::ArmorDirective srvmsg = armor.GetRequest( "ADD", "IND", "CLASS", "Susanna", "PERSON" );
102  armor.CallArmor( srvmsg );
103 
104  // get the success flag
105  // WARNING: sometimes it doesn't indicate a failure, but a
106  // common response of the aRMOR service (i.e. testing existence
107  // of an individual which doesn't exist makes the success flag false.)
108  if( !armor.Success( ) ) { /* ... */ }
109 
110  // REMEMBER TO UPDATE after the callings!
111  armor.UpdateOntology( );
112 
113 
114 
115 
116  // STEP 4 === RESPONSE
117 
118  // check the last request
119  armor_msgs::ArmorDirectiveReq& req = armor.GetLastReq( );
120  armor_msgs::ArmorDirectiveRes& res = armor.GetLastRes( );
121 
122  // print one of the sections of the last service message
123  armor.PrintLastReq( );
124  armor.PrintLastRes( );
125 
126  // generic prints
127  armor.PrintRequest( req );
128  armor.PrintResponse( res );
129 
130  // error checking
131  int last_err_code = armor.GetLastErrorCode( ); // 0:success
132  std::string error_description = armor.GetLastErrorDescription( ); // "":success ... or strange error
133 
134  return 0;
135 }
ArmorTools::PrintLastRes
void PrintLastRes()
print the last response
Definition: armor_tools.cpp:403
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
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::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
main
int main(int argc, char *argv[])
Definition: example_armor_tools_1.cpp:35
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::PrintLastReq
void PrintLastReq()
print the last request
Definition: armor_tools.cpp:413
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