RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
ArmorTools - 001 - Essential usage of ArmorTools

In this little example I want to show you which are the main features of the class ArmorTools. It can speed up really the usage of aRMOR, making easier the coding phase.

The proposed workflow is always the same:

  1. Constructor, setting the user infos
  2. Connection to the service
  3. Loading the ontology
  4. (optional) check the calidity of the connection

Done this, using armor is simple: just call a function!

Warning
this code was written only for your understanding. Probably it won't compile.
#include "ros/ros.h"
#include "armor_msgs/ArmorDirective.h"
#include "armor_msgs/ArmorDirectiveReq.h"
#include "armor_msgs/ArmorDirectiveRes.h"
#include <iostream>
#include <string>
int main( int argc, char* argv[] )
{
ros::init( argc, argv, "example_armor_tools_1" );
ros::NodeHandle nh;
// STEP 0 === CONSTRUCTOR
// constructor with no arguments:
// set default client name and reference name
// debug mode is off
// infos are stored for later in the load step
ArmorTools armor;
// another way: set your client name and reference
ArmorTools armor2( "my_client", "my_reference" );
// only debug mode, with default infos
ArmorTools armorDBmode( true );
// you can toggle the debug mode in any time using
armor.SwitchDebugMode( );
// STEP 1 === CONNECTION
// the connection to the server is stored inside the class
// using the default timeout
if( !armor.Connect( ) )
{
std::cout << "connection error!" << std::endl;
return 0;
}
// if you want to set another timeout, use this:
// armor.Connect( ros::Duration( 36 ) );
// STEP 2 === LOAD ONTOLOGY FROM FILE
// straightforward: use the dedicated function
// alternatively, you can load manually the ontology; there are several ways
if( !armor.LoadOntology( "/root/ontology/my_pizza_ontology.owl" ) )
{
// something went wrong...
}
// see ArmorTools::LoadOntology() for more details
// check the calidity of the interface
if( !armor.TestInterface( ) )
{
// something went wrong...
}
// STEP 3 === REQUEST & CALLS
// quickest way to call aRMOR
armor.SendCommand( "ADD", "IND", "CLASS", "Giampiero", "PERSON" );
// manual aRMOR call
armor_msgs::ArmorDirective srvmsg = armor.GetRequest( "ADD", "IND", "CLASS", "Susanna", "PERSON" );
armor.CallArmor( srvmsg );
// get the success flag
// WARNING: sometimes it doesn't indicate a failure, but a
// common response of the aRMOR service (i.e. testing existence
// of an individual which doesn't exist makes the success flag false.)
if( !armor.Success( ) ) { /* ... */ }
// REMEMBER TO UPDATE after the callings!
armor.UpdateOntology( );
// STEP 4 === RESPONSE
// check the last request
armor_msgs::ArmorDirectiveReq& req = armor.GetLastReq( );
armor_msgs::ArmorDirectiveRes& res = armor.GetLastRes( );
// print one of the sections of the last service message
armor.PrintLastReq( );
armor.PrintLastRes( );
// generic prints
armor.PrintRequest( req );
armor.PrintResponse( res );
// error checking
int last_err_code = armor.GetLastErrorCode( ); // 0:success
std::string error_description = armor.GetLastErrorDescription( ); // "":success ... or strange error
return 0;
}

- 001 - Essential usage of ArmorTools

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
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
main
int main(int argc, char *argv[])
Definition: example_armor_cluedo_1.cpp:26
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