OntologyClient Class
The OntologyClient class provides a common ROS service abstraction for all exploration service. More...
Header: | #include "ontologenius/clients/ontologyClients/OntologyClient.h" |
Inherits: | ClientBase |
Inherited By: | IndividualClient, ClassClient, DataPropertyClient, ObjectPropertyClient |
Namespace: | onto |
Public Functions
OntologyClient(const std::string& name) | |
std::vector<std::string> | getUp(const std::string& name, int depth = -1, const std::string& selector = "") |
bool | isA(const std::string& name, const std::string& base_class) |
std::string | getName(const std::string& name, bool take_id = true) |
std::vector<std::string> | getNames(const std::string& name, bool take_id = true) |
std::vector<std::string> | getEveryNames(const std::string& name, bool take_id = true) |
std::vector<std::string> | find(const std::string& name, bool take_id = true, const std::string& selector = "") |
std::vector<std::string> | findSub(const std::string& name, bool take_id = true, const std::string& selector = "") |
std::vector<std::string> | findRegex(const std::string& regex, bool take_id = true, const std::string& selector = "") |
std::vector<std::string> | findFuzzy(const std::string& name, double threshold = 0.5, bool take_id = true, const std::string& selector = "") |
bool | exist(const std::string& name) |
Reimplemented Public Functions
- 2 public functions inherited from ClientBase
Detailed Description
The OntologyClient class provides an abstraction common to all ontologenius exploration ROS services.
The OntologyClient implements the functions common to every ontologenius exploration.
This class is based on ClientBase and so ensure a persistent connection with the service based on. The persistent connection ensures a minimal response time. A reconnection logic is implemented in the event that the persistent connection fails.
See also IndividualClient, ClassClient, DataPropertyClient and ObjectPropertyClient.
Public Function Documentation
OntologyClient::OntologyClient(const std::string& name)
Constructs an ontology client linked to the service ontologenius/name.
std::vector<std::string> OntologyClient::getUp(const std::string& name, int depth = -1, const std::string& selector = "")
Gives all concepts below the one given in the parameter: name.
The optional depth parameter can be set to limit tree propagation to a specific value. The default value -1 represents no propagation limitation.
The optional selector parameter can be set to only get results inheriting from the selector concept. The default value "" represents no restriction on the result.
bool OntologyClient::isA(const std::string& name, const std::string& base_class)
Returns true if the concept name is or inherits of the concept base_class. This function corresponds to checking if class_base is part of the result of the function getUp applies to the concept name
std::string OntologyClient::getName(const std::string& name, bool take_id = true)
Gives one of the label of the concept name that is not muted.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::getNames(const std::string& name, bool take_id = true)
Gives all the labels of the concept name excepted the muted ones.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::getEveryNames(const std::string& name, bool take_id = true)
Gives all the labels of the concept name even the muted ones.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::find(const std::string& name, bool take_id = true, const std::string& selector = "")
Gives all the concepts having for label name.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The optional selector parameter can be set to only get results inheriting from the selector concept. The default value "" represents no restriction on the result.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::findSub(const std::string& name, bool take_id = true, const std::string& selector = "")
Gives all the concepts having for label a subset of name.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The optional selector parameter can be set to only get results inheriting from the selector concept. The default value "" represents no restriction on the result.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::findRegex(const std::string& regex, bool take_id = true, const std::string& selector = "")
Gives all concepts with a label matching the regular expression regex.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The optional selector parameter can be set to only get results inheriting from the selector concept. The default value "" represents no restriction on the result.
The result of this function depends on the setting of the working language.
std::vector<std::string> OntologyClient::findFuzzy(const std::string& name, double threshold = 0.5, bool take_id = true, const std::string& selector = "")
Gives all the names of concepts with the lowest edit distance with parameter name.
The default take_id argument can be set to false if you do not want to consider the concept identifier as a possible default name.
The optional selector parameter can be set to only get results inheriting from the selector concept. The default value "" represents no restriction on the result.
The result of this function depends on the setting of the working language and does not correspond to the concept identifiers but to other labels known by ontologenius.
The minimum editing distance can be set with the threshold parameter. This value corresponds to the number of changes to be made to pass from one word to another divided by the length of the comparison word.
bool OntologyClient::exist(const std::string& name)
Returns true if the concept name exists in the subpart of the ontology managed by the client (i.e. class, individuals, object properties, data properties).
Muted labels
Ontologenius introduces the concept of muted label. They are written <onto:label> in an OWL file.
A muted label will be useful for adding labels with errors. These labels will allow you to find a concept with an error but will make sure you never use it in output (using getName).