 |
RCL - RoboCLuedo
v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
|
Go to the documentation of this file.
28 #include "armor_msgs/ArmorDirective.h"
29 #include "armor_msgs/ArmorDirectiveReq.h"
30 #include "armor_msgs/ArmorDirectiveRes.h"
35 int main(
int argc,
char* argv[] )
37 ros::init( argc, argv,
"example_armor_tools_1" );
51 ArmorTools armor2(
"my_client",
"my_reference" );
67 std::cout <<
"connection error!" << std::endl;
80 if( !armor.
LoadOntology(
"/root/ontology/my_pizza_ontology.owl" ) )
98 armor.
SendCommand(
"ADD",
"IND",
"CLASS",
"Giampiero",
"PERSON" );
101 armor_msgs::ArmorDirective srvmsg = armor.
GetRequest(
"ADD",
"IND",
"CLASS",
"Susanna",
"PERSON" );
119 armor_msgs::ArmorDirectiveReq& req = armor.
GetLastReq( );
120 armor_msgs::ArmorDirectiveRes& res = armor.
GetLastRes( );
void PrintLastRes()
print the last response
void PrintResponse(armor_msgs::ArmorDirective &d)
print the response to the screen.
std::string GetLastErrorDescription()
last err description
armor_msgs::ArmorDirectiveReq & GetLastReq()
get a reference to the last request
void PrintRequest(armor_msgs::ArmorDirective &d)
print a request to the screen.
void SwitchDebugMode()
toggle the debug mode
armor_msgs::ArmorDirectiveRes & GetLastRes()
get a reference to the last response
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
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.
int main(int argc, char *argv[])
bool TestInterface()
check the status of the interface
bool UpdateOntology()
send the command REASON
bool Success()
check the 'success' flag referred to the last aRMOR call
bool Connect(float timeout=ARMOR_DEFAULT_TIMEOUT)
open a connection with the aRMOR service.
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
bool CallArmor(armor_msgs::ArmorDirective &data)
send a command to the aRMOR service.
A minimal C++ client for aRMOR.
void PrintLastReq()
print the last request
A minimal C++ client for aRMOR.
int GetLastErrorCode()
err code referred to the last call