Skip to content

Commit

Permalink
fix naming
Browse files Browse the repository at this point in the history
  • Loading branch information
sarthou committed Jun 9, 2024
1 parent d391cef commit 38df470
Show file tree
Hide file tree
Showing 20 changed files with 419 additions and 196 deletions.
445 changes: 333 additions & 112 deletions docs/cpp_API/FeederPublisher.html

Large diffs are not rendered by default.

26 changes: 13 additions & 13 deletions include/ontologenius/API/ontologenius/FeederPublisher.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace onto {
/// @param on is the object of the triplet to add.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addProperty(const std::string& from, const std::string& property, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addProperty(const std::string& from, const std::string& property, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Adds the fact that "from" is linked to the data "value" of type "type" by the property "property".
/// At least "from" must be already known to the system.
/// The property can be unknown before calling this function.
Expand All @@ -55,49 +55,49 @@ namespace onto {
/// @param value is the value of the triplet object.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addProperty(const std::string& from, const std::string& property, const std::string& type, const std::string& value, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addProperty(const std::string& from, const std::string& property, const std::string& type, const std::string& value, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Adds the inheratage: "from" is a "on". "from" and "on" could by a class, an individual or a property.
/// At least from or on must be already known to the system. If one of them is unknown, it will be automatically created.
/// @param from is the parent concept. It could by a class, an individual or a property.
/// @param on is the child concept. It could by a class, an individual or a property.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addInheritage(const std::string& from, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addInheritage(const std::string& from, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Adds the label "name" in the language "lang" to the class, individual, or property "from".
/// "from" must be already known to the system.
/// @param from is the concept (individual, class, property) to which add a name in natural language.
/// @param lang is the language indentifier (en, fr, de, ...).
/// @param name is the concept name in natural language.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addLanguage(const std::string& from, const std::string& lang, const std::string& name, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addLanguage(const std::string& from, const std::string& lang, const std::string& name, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Adds a class or individual.
/// @param from the individual or class to add.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addConcept(const std::string& from, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addConcept(const std::string& from, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Adds an object property inverse axiom.
/// @param property is the object property for which its inverse is define.
/// @param inverse_property is the inverse property of the previous object property.
/// @param stamp is the time at which the added relation become true.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void addInverseOf(const std::string& property, const std::string& inverse_property, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void addInverseOf(const std::string& property, const std::string& inverse_property, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());

/// @brief Removes the fact that "from" is linked to any object by the property "property".
/// After this action, knowledge of the property is not removed.
/// @param from is the subject of the triplet to remove.
/// @param property is the predicat of the triplet to remove.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeProperty(const std::string& from, const std::string& property, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeProperty(const std::string& from, const std::string& property, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes the fact that "from" is linked with "on" by the property "property".
/// After this action, knowledge of the property is not removed.
/// @param from is the subject of the triplet to remove.
/// @param property is the predicat of the triplet to remove.
/// @param on is the object of the triplet to remove.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeProperty(const std::string& from, const std::string& property, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeProperty(const std::string& from, const std::string& property, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes the fact that "from" is linked to the data "value" of type "type" by the property "property".
/// After this action, knowledge of the property is not removed.
/// @param from is the subject of the triplet to remove.
Expand All @@ -106,32 +106,32 @@ namespace onto {
/// @param value is the value of the triplet object.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeProperty(const std::string& from, const std::string& property, const std::string& type, const std::string& value, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeProperty(const std::string& from, const std::string& property, const std::string& type, const std::string& value, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes the inheratage: "from" is a "on". "from" and "on" could by a class, an individual or a property.
/// @param from is the parent concept. It could by a class, an individual or a property.
/// @param on is the child concept. It could by a class, an individual or a property.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeInheritage(const std::string& from, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeInheritage(const std::string& from, const std::string& on, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes the label "name" in the language "lang" to the class, individual, or property "from".
/// @param from is the concept (individual, class, property) to which remove a name in natural language.
/// @param lang is the language indentifier (en, fr, de, ...).
/// @param name is the concept name in natural language.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeLanguage(const std::string& from, const std::string& lang, const std::string& name, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeLanguage(const std::string& from, const std::string& lang, const std::string& name, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes a class or individual.
/// All inheritance, properties, and labels applied to "from" are also removed
/// @param from the individual or class to remove.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeConcept(const std::string& from, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeConcept(const std::string& from, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());
/// @brief Removes an object property inverse axiom.
/// @param property is the object property for which its inverse has to be removed.
/// @param inverse_property is the inverse property of the previous object property.
/// @param stamp is the time at which the added relation become false.
/// If the time stamp stamp is not defined, the function takes the current ROS time as the time stamp.
void removeInverseOf(const std::string& property, const std::string& inverse_property, const onto_ros::Time& stamp = onto_ros::Node::get().current_time());
void removeInverseOf(const std::string& property, const std::string& inverse_property, const onto_ros::Time& stamp = onto_ros::Node::get().currentTime());

/// @brief Returns the number of subscribers that are currently connected to the internal ROS publisher.
size_t getNumSubscribers() { return stamped_pub_.getNumSubscribers(); }
Expand Down
12 changes: 6 additions & 6 deletions include/ontologenius/API/ontologenius/clients/ClientBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,33 +54,33 @@ namespace onto {
{
cpt++;

auto req = ontologenius::compat::make_request<ontologenius::compat::OntologeniusService>();
auto res = ontologenius::compat::make_response<ontologenius::compat::OntologeniusService>();
auto req = ontologenius::compat::makeRequest<ontologenius::compat::OntologeniusService>();
auto res = ontologenius::compat::makeResponse<ontologenius::compat::OntologeniusService>();

[action, param](auto&& req) {
req->action = action;
req->param = param;
}(ontologenius::compat::onto_ros::getServicePointer(req));

using ResultTy = typename decltype(client_)::Status;
using ResultTy = typename decltype(client_)::Status_e;

switch(client_.call(req, res))
{
case ResultTy::SUCCESSFUL_WITH_RETRIES:
case ResultTy::ros_status_successful_with_retry:
{
if(client_verbose)
std::cout << COLOR_GREEN << "Restored ontologenius/" << name_ << COLOR_OFF << std::endl;
[[fallthrough]];
}
case ResultTy::SUCCESSFUL:
case ResultTy::ros_status_successful:
{
return [&](auto&& res) {
code = res->code;
error_code_ = res->code;
return res->values;
}(ontologenius::compat::onto_ros::getServicePointer(res));
}
case ResultTy::FAILURE:
case ResultTy::ros_status_failure:
[[fallthrough]];
default:
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,33 +54,33 @@ namespace onto {
{
cpt++;

auto req = ontologenius::compat::make_request<ontologenius::compat::OntologeniusIndexService>();
auto res = ontologenius::compat::make_response<ontologenius::compat::OntologeniusIndexService>();
auto req = ontologenius::compat::makeRequest<ontologenius::compat::OntologeniusIndexService>();
auto res = ontologenius::compat::makeResponse<ontologenius::compat::OntologeniusIndexService>();

[action, param](auto&& req) {
req->action = action;
req->param = param;
}(ontologenius::compat::onto_ros::getServicePointer(req));

using ResultTy = typename decltype(client_)::Status;
using ResultTy = typename decltype(client_)::Status_e;

switch(client_.call(req, res))
{
case ResultTy::SUCCESSFUL_WITH_RETRIES:
case ResultTy::ros_status_successful_with_retry:
{
if(client_verbose)
std::cout << COLOR_GREEN << "Restored ontologenius/" << name_ << COLOR_OFF << std::endl;
[[fallthrough]];
}
case ResultTy::SUCCESSFUL:
case ResultTy::ros_status_successful:
{
return [&](auto&& res) {
code = res->code;
error_code_ = res->code;
return res->string_values;
}(ontologenius::compat::onto_ros::getServicePointer(res));
}
case ResultTy::FAILURE:
case ResultTy::ros_status_failure:
{
if(client_verbose)
std::cout << COLOR_ORANGE << "Failed to call call ontologenius/" << name_ << COLOR_OFF << std::endl;
Expand All @@ -101,33 +101,33 @@ namespace onto {
{
cpt++;

auto req = ontologenius::compat::make_request<ontologenius::compat::OntologeniusIndexService>();
auto res = ontologenius::compat::make_response<ontologenius::compat::OntologeniusIndexService>();
auto req = ontologenius::compat::makeRequest<ontologenius::compat::OntologeniusIndexService>();
auto res = ontologenius::compat::makeResponse<ontologenius::compat::OntologeniusIndexService>();

[action, param](auto&& req) {
req->action = action;
req->param = param;
}(ontologenius::compat::onto_ros::getServicePointer(req));

using ResultTy = typename decltype(client_)::Status;
using ResultTy = typename decltype(client_)::Status_e;

switch(client_.call(req, res))
{
case ResultTy::SUCCESSFUL_WITH_RETRIES:
case ResultTy::ros_status_successful_with_retry:
{
if(client_verbose)
std::cout << COLOR_GREEN << "Restored ontologenius/" << name_ << COLOR_OFF << std::endl;
[[fallthrough]];
}
case ResultTy::SUCCESSFUL:
case ResultTy::ros_status_successful:
{
return [&](auto&& res) {
code = res->code;
error_code_ = res->code;
return res->index_values;
}(ontologenius::compat::onto_ros::getServicePointer(res));
}
case ResultTy::FAILURE:
case ResultTy::ros_status_failure:
{
if(client_verbose)
std::cout << COLOR_ORANGE << "Failed to call call ontologenius/" << name_ << COLOR_OFF << std::endl;
Expand Down
28 changes: 14 additions & 14 deletions include/ontologenius/compat/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,10 +73,10 @@ namespace ontologenius::compat {
using ResponseType = typename T::Response;

template<typename T, typename Request_ = typename T::Request>
inline auto make_request() { return Request_(); }
inline auto makeRequest() { return Request_(); }

template<typename T, typename Response_ = typename T::Response>
inline auto make_response() { return Response_(); }
inline auto makeResponse() { return Response_(); }

// todo: RequestType, ResponseType

Expand All @@ -97,10 +97,10 @@ namespace ontologenius::compat {
using ResponseType = std::shared_ptr<typename T::Response>;

template<typename T, typename Request_ = typename T::Request>
inline auto make_request() { return std::make_shared<Request_>(); }
inline auto makeRequest() { return std::make_shared<Request_>(); }

template<typename T, typename Response_ = typename T::Response>
inline auto make_response() { return std::make_shared<Response_>(); }
inline auto makeResponse() { return std::make_shared<Response_>(); }

// template <typename T, typename Result_ = typename T::>
#endif
Expand Down Expand Up @@ -202,7 +202,7 @@ namespace ontologenius::compat {

void spin();

Time current_time();
Time currentTime();

private:
explicit Node(const std::string& node_name);
Expand Down Expand Up @@ -329,11 +329,11 @@ namespace ontologenius::compat {
class Client
{
public:
enum class Status
enum class Status_e
{
SUCCESSFUL,
SUCCESSFUL_WITH_RETRIES,
FAILURE
ros_status_successful,
ros_status_successful_with_retry,
ros_status_failure
};

explicit Client(const std::string& service_name) : name_(service_name)
Expand All @@ -347,10 +347,10 @@ namespace ontologenius::compat {
#endif
}

Status call(const ontologenius::compat::RequestType<T>& req, ontologenius::compat::ResponseType<T>& res)
Status_e call(const ontologenius::compat::RequestType<T>& req, ontologenius::compat::ResponseType<T>& res)
{
using namespace std::chrono_literals;
auto status = Status::FAILURE;
auto status = Status_e::ros_status_failure;

#if ONTO_ROS_VERSION == 1
T srv;
Expand All @@ -361,13 +361,13 @@ namespace ontologenius::compat {
handle_ = node.handle_.serviceClient<T>(name_, true);
if(handle_.call(srv))
{
status = Status::SUCCESSFUL_WITH_RETRIES;
status = Status_e::ros_status_successful_with_retry;
res = srv.response;
}
}
else
{
status = Status::SUCCESSFUL;
status = Status_e::ros_status_successful;
res = srv.response;
}

Expand All @@ -381,7 +381,7 @@ namespace ontologenius::compat {

if(future.wait_for(5s) == std::future_status::ready)
{
status = Status::SUCCESSFUL;
status = Status_e::ros_status_successful;
res = future.get();
}
#endif
Expand Down
2 changes: 1 addition & 1 deletion include/ontologenius/core/feeder/FeederEcho.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace ontologenius {
// should we perhaps unlock the mutex...?
}

void add(const std::string& data, const compat::onto_ros::Time& stamp = compat::onto_ros::Node::get().current_time())
void add(const std::string& data, const compat::onto_ros::Time& stamp = compat::onto_ros::Node::get().currentTime())
{
mut_.lock();
echo_messages_.emplace_back(data, stamp);
Expand Down
2 changes: 1 addition & 1 deletion include/ontologenius/core/ontoGraphs/Graphs/ClassGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ namespace ontologenius {
void getWith(ClassBranch* first_class, index_t second_class, std::unordered_set<std::string>& res, std::unordered_set<index_t>& do_not_take, uint32_t current_depth, int& found_depth, int depth_prop, std::unordered_set<ClassBranch*>& next_step);
void getWith(ClassBranch* first_class, index_t second_class, std::unordered_set<index_t>& res, std::unordered_set<index_t>& do_not_take, uint32_t current_depth, int& found_depth, int depth_prop, std::unordered_set<ClassBranch*>& next_step);
template<typename T>
void getWith_(ClassBranch* first_class, index_t second_class, std::unordered_set<T>& res, std::unordered_set<index_t>& do_not_take, uint32_t current_depth, int& found_depth, int depth_prop, std::unordered_set<ClassBranch*>& next_step);
void getWithTemplate(ClassBranch* first_class, index_t second_class, std::unordered_set<T>& res, std::unordered_set<index_t>& do_not_take, uint32_t current_depth, int& found_depth, int depth_prop, std::unordered_set<ClassBranch*>& next_step);
void getDomainOf(ClassBranch* branch, std::unordered_set<std::string>& res, int depth = -1);
void getDomainOf(ClassBranch* branch, std::unordered_set<index_t>& res, int depth = -1);
void getRangeOf(ClassBranch* branch, std::unordered_set<std::string>& res, int depth = -1);
Expand Down
4 changes: 2 additions & 2 deletions include/ontologenius/core/ontoGraphs/Graphs/Graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -571,7 +571,7 @@ namespace ontologenius {

if(use_default)
{
std::string tmp = branch->value();
const std::string& tmp = branch->value();
if(std::regex_match(tmp, match, base_regex))
return true;
}
Expand Down Expand Up @@ -637,7 +637,7 @@ namespace ontologenius {
LevenshteinDistance dist;

std::shared_lock<std::shared_timed_mutex> lock(mutex_);
for(auto branch : this->all_branchs_)
for(auto* branch : this->all_branchs_)
{
if(use_default)
if((tmp_cost = dist.get(branch->value(), value)) <= lower_cost)
Expand Down
Loading

0 comments on commit 38df470

Please sign in to comment.