CLASS armor_tools.cpp

class aRMOR Tools – header

A minimal C++ client for aRMOR.

See also

ArmorCluedo

See also

ArmorTools

Authors

Francesco Ganci (S4143910)

Version

v1.0

Defines

ARMOR_DEFAULT_URI
ARMOR_DEFAULT_REASONER
ARMOR_DEFAULT_CLIENT
ARMOR_DEFAULT_REFERENCE
ARMOR_DEFAULT_TIMEOUT
ARMOR_DEFAULT_DEBUGMODE
ARMOR_SERVICE_SINGLE_REQUEST
ARMOR_SERVICE_MULTIPLE_REQUESTS
ARMOR_CLASS_LABEL
ARMOR_INFO(msg)
ARMOR_ERR(msg)
ARMOR_CHECK_INTERFACE(returnval)
ARMOR_RES(msg)
ARMOR_RES_QUERY(msg)
SS(this_string)
SSS(this_thing)
BOOL_TO_CSTR(booleanvalue)
LOGSQUARE(str)
class ArmorTools
#include <armor_tools.h>

A minimal C++ client for aRMOR.

The class ArmorTools aims at giving a first abstraction of the service aRMOR by providing few “shortcuts”. A strong point of this interface lies in the fact that a roscpp node can communicate with aRMOR through functions instead of direct callings to the service.

Another important feature is the debug mode: the programmer can turn on and off the messages inside the code, in order to understand what is going on “underneath the hood”.

The class lets the programmer to not waste time in fill in the ArmorDirective message each time: client_name and reference_name

are set only once in the constructor, whereas the remaining fields can be set using functions. Also the connection is contained in the class, and there are checks for understanding if the connection is valid or not.

In the end, the class stores the last request and the last response at each call, so the programmer can easily retrieve them and print, again using function calls.

Todo:

actually the class has some methods missing, for example methods for modifying client name and reference name.

Todo:

sequential commands to aRMOR is not supported right now: only the single command service is used.

Todo:

the interface actually can load the ontology only from file. It could be a good idea to have tools also for loading it from another source.

See also

ArmorCluedo an applciation of this interface

Subclassed by ArmorCluedo, ArmorCluedo

Public Functions

ArmorTools(std::string client = ARMOR_DEFAULT_CLIENT, std::string reference = ARMOR_DEFAULT_REFERENCE, bool dbmode = false)

Class Constructor, 3 arguments.

Complete class constructor. Dummy init of the class in an invalid state.

See also

aRMOR official documentation &#8212; meaning of the parameters “client” and “reference”

Parameters
  • client – (optional) corresponding to the ‘client_name’ field

  • reference – (optional) corresponding to the ‘reference_name’ field

  • dbmode – (optional) enable debug mode?

ArmorTools(bool dbmode)

Class Constructor, only one argument.

class constructor with only debug mode. Dummy init of the class in an invalid state.

Parameters

dbmode – debug mode?

~ArmorTools()

class destructor (empty)

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

This function writes the aRMOR directive request in one shot.

Parameters
  • command – (mandatory) the main command

  • first_spec – (optional) the first specifier

  • second_spec – (optional) the second specifier

  • arg – (optional) (from 1 to 5) the arguments of the request

Returns

the complete aRMOR directve message with the request part ready to use.

bool CallArmor(armor_msgs::ArmorDirective &data)

send a command to the aRMOR service.

This function performs the call to the aRMOR service ARMOR_SERVICE_SINGLE_REQUEST given the entire message to send to.

Todo:

there’s no way to compose aRMOR commands in a list. actually ARMOR_SERVICE_MULTIPLE_REQUESTS is unused.

Parameters

data – reference to the request to send

Returns

false if there’s not coenction, or if the request went wrong. true otherwise.

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.

the function call the aRMOR service in order to make it load one file with extension .owl as ontology base. The file is only read, so the ontology will not alter it.

Note

If you want to manage multiple aRMOR sessions, please consider to construct more than one ArmorTools object.

Parameters
  • path – the path of the .owl ontology file

  • uri – the URI of the ontology (the main identifier)

  • manipulationFlag – if enabled, the ontology will wait for the command APPLY before executing the manipulation commands

  • reasoner – one among “HERMIT”, “PELLET” (default), “FACT”, “SNOROCKET”

  • bufferend_reasoner – if enabled, the ontology will wait for the command REASON before updating its internal state.

Returns

success or not

bool Connect(float timeout = ARMOR_DEFAULT_TIMEOUT)

open a connection with the aRMOR service.

This function simply asks the aRMOR service client. The client handle is stored inside the class, so you don’t have to worry about it.

Note

The function returns false anso when, after opened the connection, you try to connect again. This is not allowed: you cannot reconnect.

Parameters

timeout – how much time to wait until to stop the connection attempt; see ARMOR_DEFAULT_TIMEOUT .

Returns

success or not

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.

Just a shortcut for the couple ArmorTools::Connect then ArmorTools::LoadOntology .

See also

ArmorTools::Connect connection to the aRMOR service

See also

ArmorTools::LoadOntology loading ontology from file, and arguments

Returns

success or not

bool SaveOntology(std::string path)

save the ontology on file

Shortcut for the aRMOR command SAVE INFERENCE. It writes the actual state of the ontology on a file. If the file doesn’t exist, it will be created. The ontology is updated before the writing on file.

Parameters

path – where to save the .owl file

Returns

success or not

bool UpdateOntology()

send the command REASON

Depending on the configuration used in ArmorTools::LoadOntology, the aRMOR command REASON is needed in order to update the current state of the ontology (aka infer something

).

This function is a shortcut for the command

REASON.

Warning

often not using this function is source of errors! Please remember to use it, because the other function won’t do it automatically.

Returns

success or not

void PrintRequest(armor_msgs::ArmorDirective &d)

print a request to the screen.

Parameters

d – the entire aRMOR directive message.

void PrintResponse(armor_msgs::ArmorDirective &d)

print the response to the screen.

Parameters

d – the entire aRMOR directive message.

void SwitchDebugMode()

toggle the debug mode

This function switches the value ArmorTools::DebugMode each time it is called.

int GetLastErrorCode()

err code referred to the last call

Returns

the last error code

std::string GetLastErrorDescription()

last err description

Returns

the last error description

bool Success()

check the ‘success’ flag referred to the last aRMOR call

Warning

sometimes aRMOR uses the false answer as the correct answer, violating the semantic of the flag ‘success’. A case is the command QUERY IND which causes aRMOR to reply with success=false.

Returns

success or not

bool LoadedOntology()

check if the ontology was loaded or not

Returns

loaded or not

bool TestInterface()

check the status of the interface

Returns

valid inferface or not

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

Shortcut for the couple ArmorTools::GetRequest and Armor::CallArmor.

Parameters
  • command – (mandatory) the main command

  • first_spec – (optional) the first specifier

  • second_spec – (optional) the second specifier

  • arg – (optional) (from 1 to 5) the arguments of the request

  • printResponse – print the request before calling the service

Returns

success or not

armor_msgs::ArmorDirectiveRes &GetLastRes()

get a reference to the last response

Returns

reference to the last response

armor_msgs::ArmorDirectiveReq &GetLastReq()

get a reference to the last request

Returns

last sent request to aRMOR

void PrintLastRes()

print the last response

void PrintLastReq()

print the last request

Protected Attributes

bool DebugMode = false

debug mode enabled or not

Private Functions

bool FileExist(std::string path)

Private Members

ros::ServiceClient ArmorSrv
std::string ClientName = ARMOR_DEFAULT_CLIENT
std::string ReferenceName = ARMOR_DEFAULT_REFERENCE
std::string uri = ARMOR_DEFAULT_URI
bool IsLoadedInterface = false
armor_msgs::ArmorDirectiveRes LastRes
armor_msgs::ArmorDirectiveReq LastReq

class aRMOR Tools – cpp implementation

implementation of the class ArmorTools

See also

armor_tools.h

Author

Francesco Ganci (S4143910)

Version

v1.0