From 3f816329e12fc2095ee662bfdfbd13a0dc0b27da Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Sun, 22 Mar 2020 23:20:18 +0100 Subject: [PATCH 01/13] Reconfiguration data gets succesfully transfered to the Knowledgeengine. Now a communication between Knowledge and RS needs to be implemented via PrologCPPQueries and some additional rules to check if a annotator can be reconfigured to meet the requested requirements. In order to achieve this final communication, an additonal reconfiguration service needs to be implemented. --- .../descriptors/analysis_engines/demo.yaml | 1 + .../annotation/SacModelAnnotator.yaml | 27 ++- .../src/annotation/src/SacModelAnnotator.cpp | 200 +++++++++++------- .../core/include/robosherlock/utils/common.h | 8 + .../flowcontrol/RSProcessManager.h | 14 ++ .../flowcontrol/YamlToXMLConverter.h | 11 +- .../src/RSAggregateAnalysisEngine.cpp | 6 + .../src/flowcontrol/src/RSProcessManager.cpp | 12 ++ .../flowcontrol/src/YamlToXMLConverter.cpp | 107 ++++++++-- .../queryanswering/KnowledgeEngine.h | 16 ++ 10 files changed, 307 insertions(+), 95 deletions(-) diff --git a/robosherlock/descriptors/analysis_engines/demo.yaml b/robosherlock/descriptors/analysis_engines/demo.yaml index 5027b02b..f5edd174 100644 --- a/robosherlock/descriptors/analysis_engines/demo.yaml +++ b/robosherlock/descriptors/analysis_engines/demo.yaml @@ -9,5 +9,6 @@ fixedflow: - ImageSegmentationAnnotator - PointCloudClusterExtractor - ClusterMerger + - SacModelAnnotator CollectionReader: camera_config_files: ['config_kinect_robot.ini'] diff --git a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml index 95aef3fd..7b8893d5 100644 --- a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml +++ b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml @@ -1,6 +1,7 @@ annotator: implementation: rs_SacModelAnnotator name: SacModelAnnotator + capabilities: inputs: - rs.scene.MergedHypothesis @@ -8,6 +9,7 @@ capabilities: outputs: - rs.annotation.Shape: [cylinder] domain: [cylinder] + parameters: apply_to_clusters: true distanceThreshold: 0.05 @@ -19,5 +21,28 @@ parameters: minPoints: 200 radiusLimit1: 0.01 radiusLimit2: 0.5 - sacModel: 6 + sacModel: 5 useNormals: true + +reconfiguration: + # Definition of sphere reconfiguration + setup_spheres: + capabilities: + outputs: + - rs.annotation.Shape: [sphere] + domain: [sphere] + + # Overwrite or define new parameters: + parameters: + test_param: "success" + sacModel: 4 + + # Example setup + setup_example: + capabilities: + outputs: + - rs.annotation.Shape: [example] + domain: [example] + + parameters: + useNormals: false \ No newline at end of file diff --git a/robosherlock/src/annotation/src/SacModelAnnotator.cpp b/robosherlock/src/annotation/src/SacModelAnnotator.cpp index 68be7004..96ce75c6 100644 --- a/robosherlock/src/annotation/src/SacModelAnnotator.cpp +++ b/robosherlock/src/annotation/src/SacModelAnnotator.cpp @@ -44,89 +44,134 @@ class SacModelAnnotator : public Annotator { private: - bool apply_to_clusters; + bool apply_to_clusters; + pcl::SacModel sacModel; + std::string name; + + TyErrorId readParameters(AnnotatorContext &ctx) { + if(ctx.isParameterDefined("sacModel")) + { + int selectedModel; + ctx.extractValue("sacModel", selectedModel); + + switch(selectedModel) { + case pcl::SACMODEL_CYLINDER: // 5 + name = "CYLINDER"; + break; + case pcl::SACMODEL_SPHERE: // 4 + name = "SPHERE"; + break; + case pcl::SACMODEL_CIRCLE2D: // 2 + name = "CIRCLE"; + break; + case pcl::SACMODEL_PLANE: // 0 + name = "PLANE"; + break; + + default: + return UIMA_ERR_NOT_YET_IMPLEMENTED; + } + + sacModel = static_cast(selectedModel); + outInfo("Selected " << name << " (" << sacModel << ").."); + + return UIMA_ERR_NONE; + } + + return UIMA_ERR_ANNOTATOR_COULD_NOT_LOAD; + } public: - TyErrorId initialize(AnnotatorContext &ctx) - { - outInfo("initialize"); - return UIMA_ERR_NONE; - } - - TyErrorId destroy() - { - outInfo("destroy"); - return UIMA_ERR_NONE; - } - - TyErrorId process(CAS &tcas, ResultSpecification const &resSpec) - { - MEASURE_TIME; - outInfo("process begins"); - - rs::SceneCas cas(tcas); - rs::Scene scene = cas.getScene(); - - pcl::PointCloud::Ptr cloud_ptr(new pcl::PointCloud); - pcl::PointCloud::Ptr normals_ptr(new pcl::PointCloud); - cas.get(VIEW_CLOUD, *cloud_ptr); - cas.get(VIEW_NORMALS, *normals_ptr); - - - std::vector clusters; - scene.identifiables.filter(clusters); - outInfo("Processing " << clusters.size() << " point clusters"); - for(std::vector::iterator it = clusters.begin(); it != clusters.end(); ++it) + TyErrorId initialize(AnnotatorContext &ctx) { - pcl::PointIndicesPtr clusterIndices(new pcl::PointIndices()); - rs::conversion::from(((rs::ReferenceClusterPoints)it->points.get()).indices(), *clusterIndices); - + outInfo("initialize"); - pcl::PointCloud::Ptr clusterCloud(new pcl::PointCloud()); - pcl::PointCloud::Ptr clusterNormal(new pcl::PointCloud); - pcl::ModelCoefficients::Ptr coefficients_cylinder(new pcl::ModelCoefficients); - pcl::PointIndices::Ptr cylinderInliers(new pcl::PointIndices); + return readParameters(ctx); + } - for(std::vector::const_iterator pit = clusterIndices->indices.begin(); - pit != clusterIndices->indices.end(); pit++) - { - clusterCloud->points.push_back(cloud_ptr->points[*pit]); - clusterNormal->points.push_back(normals_ptr->points[*pit]); - } + TyErrorId reconfigure() + { + outInfo("Reconfiguring"); - clusterCloud->width = clusterCloud->points.size(); - clusterCloud->height = 1; - clusterCloud->is_dense = true; - clusterNormal->width = normals_ptr->points.size(); - clusterNormal->height = 1; - clusterNormal->is_dense = true; - outDebug("Fitting the selected SAC model"); - - pcl::SACSegmentationFromNormals seg; - seg.setOptimizeCoefficients(true); - seg.setModelType(pcl::SACMODEL_CYLINDER); - seg.setMethodType(pcl::SAC_RANSAC); - seg.setNormalDistanceWeight(0.1); - seg.setMaxIterations(1000); - seg.setDistanceThreshold(0.03); - seg.setRadiusLimits(0, 0.1); - seg.setInputCloud(clusterCloud); - seg.setInputNormals(clusterNormal); - - // Obtain the cylinder inliers and coefficients - seg.segment(*cylinderInliers, *coefficients_cylinder); - - outDebug("Size of cluster " << it - clusters.begin() << ": " << clusterCloud->width); - outDebug("Number of CYLINDER inliers: " << cylinderInliers->indices.size()); - if((float)cylinderInliers->indices.size() / clusterCloud->width > 0.5) - { - rs::Shape shapeAnnotation = rs::create(tcas); - shapeAnnotation.shape.set("cylinder"); - it->annotations.append(shapeAnnotation); - } + AnnotatorContext &ctx = getAnnotatorContext(); + return readParameters(ctx); + } + + TyErrorId destroy() + { + outInfo("destroy"); + return UIMA_ERR_NONE; + } + + TyErrorId process(CAS &tcas, ResultSpecification const &resSpec) + { + MEASURE_TIME; + outInfo("process begins"); + + rs::SceneCas cas(tcas); + rs::Scene scene = cas.getScene(); + + pcl::PointCloud::Ptr cloud_ptr(new pcl::PointCloud); + pcl::PointCloud::Ptr normals_ptr(new pcl::PointCloud); + cas.get(VIEW_CLOUD, *cloud_ptr); + cas.get(VIEW_NORMALS, *normals_ptr); + + std::vector clusters; + scene.identifiables.filter(clusters); + outInfo("Processing " << clusters.size() << " point clusters"); + for(std::vector::iterator it = clusters.begin(); it != clusters.end(); ++it) + { + pcl::PointIndicesPtr clusterIndices(new pcl::PointIndices()); + rs::conversion::from(((rs::ReferenceClusterPoints)it->points.get()).indices(), *clusterIndices); + + + pcl::PointCloud::Ptr clusterCloud(new pcl::PointCloud()); + pcl::PointCloud::Ptr clusterNormal(new pcl::PointCloud); + + pcl::ModelCoefficients::Ptr coefficientsModel(new pcl::ModelCoefficients); + + pcl::PointIndices::Ptr modelInliers(new pcl::PointIndices); + + for(std::vector::const_iterator pit = clusterIndices->indices.begin(); + pit != clusterIndices->indices.end(); pit++) + { + clusterCloud->points.push_back(cloud_ptr->points[*pit]); + clusterNormal->points.push_back(normals_ptr->points[*pit]); + } + + clusterCloud->width = clusterCloud->points.size(); + clusterCloud->height = 1; + clusterCloud->is_dense = true; + clusterNormal->width = normals_ptr->points.size(); + clusterNormal->height = 1; + clusterNormal->is_dense = true; + outInfo("Fitting the " << name << " SAC model"); + + pcl::SACSegmentationFromNormals seg; + seg.setOptimizeCoefficients(true); + seg.setModelType(sacModel); + seg.setMethodType(pcl::SAC_RANSAC); + seg.setNormalDistanceWeight(0.1); + seg.setMaxIterations(1000); + seg.setDistanceThreshold(0.03); + seg.setRadiusLimits(0, 0.1); + seg.setInputCloud(clusterCloud); + seg.setInputNormals(clusterNormal); + + // Obtain the cylinder inliers and coefficients + seg.segment(*modelInliers, *coefficientsModel); + + outDebug("Size of cluster " << it - clusters.begin() << ": " << clusterCloud->width); + outInfo("Number of " << name << " inliers: " << modelInliers->indices.size()); + if((float)modelInliers->indices.size() / clusterCloud->width > 0.5) + { + rs::Shape shapeAnnotation = rs::create(tcas); + shapeAnnotation.shape.set(name); + it->annotations.append(shapeAnnotation); + } #if DEBUG_OUTPUT - pcl::ExtractIndices extract; + pcl::ExtractIndices extract; extract.setInputCloud(clusterCloud); extract.setIndices(cylinderInliers); extract.setNegative(false); @@ -144,10 +189,9 @@ class SacModelAnnotator : public Annotator writer.write(fn.str(), *cloud_cylinder, false); } #endif + } + return UIMA_ERR_NONE; } - return UIMA_ERR_NONE; - } - }; MAKE_AE(SacModelAnnotator) diff --git a/robosherlock/src/core/include/robosherlock/utils/common.h b/robosherlock/src/core/include/robosherlock/utils/common.h index 7a965238..f3589f58 100644 --- a/robosherlock/src/core/include/robosherlock/utils/common.h +++ b/robosherlock/src/core/include/robosherlock/utils/common.h @@ -57,6 +57,14 @@ struct AnnotatorCapabilities * @brief iTypeValueRestrictions mapping between input type and possible values (if no restrictions on values vector is empty) */ std::map> iTypeValueRestrictions; + /** + * @brief rOutputTypeValueDomains mapping of output domain values after reconfiguring + */ + std::map> rOutputTypeValueDomains; + /** + * @brief rInputTypeValueRestrictions mapping of input restrictions after reconfiguring + */ + std::map> rInputTypeValueRestrictions; }; diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h index 8185c1bf..05d6ddd5 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h @@ -145,6 +145,20 @@ class RSProcessManager */ bool resetAE(std::string); + /** + * @brief Reconfigures a single annotator + * @param annotatorIdx Index of annotator in pipeline + * @return true on success + */ + bool reconfigureAnnotator(int annotatorIdx); + + /** + * @brief Reconfigures a single annotator + * @param annotatorName Name of annotator in pipeline + * @return true on success + */ + bool reconfigureAnnotator(std::string &annotatorName); + /** * @brief setUseIdentityResolution run identiy resolution for tracking objects over multiple scenes * @param useIdentityResoltuion diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h index d0b73913..392c42de 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h @@ -126,22 +126,27 @@ class YamlToXMLConverter string getType(const YAML::Node& node); string getTypeFilePath() const; - bool genAEInfo(const YAML::Node& node); + // TODO: Why identical function implementation? + //bool genAEInfo(const YAML::Node& node); bool parseAnnotatorInfo(const YAML::Node& node); bool generateAnnotatorConfigParamInfo(const YAML::Node& node); bool genConfigParamInfo(const YAML::Node& node, const string analysisEngineName); - bool parseCapabInfo(const YAML::Node& node, std::string annotator_name = ""); + bool parseCapabInfo(const YAML::Node& node, string annotator_name = "", string setup_name = ""); bool genCapabInfo(const YAML::Node& node); bool genFlowConstraints(const YAML::Node& node); bool genFsIndexCollection(); + bool parseReconfigurationInfo(const YAML::Node &node); - rs::AnnotatorCapabilities annotatorCap; + rs::AnnotatorCapabilities annotCap; // parsing + rs::AnnotatorCapabilities annotatorCap; // return value std::vector overwrittenAnnotCaps; vector delegates_; + + }; #endif diff --git a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp index 00960571..deb3eaf4 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -394,6 +394,12 @@ std::string convertAnnotatorYamlToXML(std::string annotator_name, if (delegate_capabilities[annotator_name].iTypeValueRestrictions.empty()) delegate_capabilities[annotator_name].iTypeValueRestrictions = converter.getAnnotatorCapabilities().iTypeValueRestrictions; + if (delegate_capabilities[annotator_name].rOutputTypeValueDomains.empty()) + delegate_capabilities[annotator_name].rOutputTypeValueDomains = + converter.getAnnotatorCapabilities().rOutputTypeValueDomains; + if(delegate_capabilities[annotator_name].rInputTypeValueRestrictions.empty()) + delegate_capabilities[annotator_name].rInputTypeValueRestrictions = + converter.getAnnotatorCapabilities().rInputTypeValueRestrictions; } } catch (YAML::ParserException e) diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 06670266..e1a80167 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -573,6 +573,18 @@ bool RSProcessManager::highlightResultsInCloud(const std::vector &filter, return true; } +bool RSProcessManager::reconfigureAnnotator(int annotatorIdx) { + if(annotatorIdx >= 0 && annotatorIdx < engine_->iv_annotatorMgr.iv_vecEntries.size()) { + return engine_->iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; + } + + return false; +} + +bool RSProcessManager::reconfigureAnnotator(std::string &annotatorName) { + return reconfigureAnnotator(engine_->getIndexOfAnnotator(std::move(annotatorName))); +} + template bool RSProcessManager::drawResultsOnImage(const std::vector &filter, const std::vector &resultDesignators, std::string &requestJson, cv::Mat &resImage); diff --git a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp index 367f5c2c..a67caade 100644 --- a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp +++ b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp @@ -17,6 +17,7 @@ static const string AE_NODE_NAME = "ae"; static const string ANNOTATOR_NODE_NAME = "annotator"; static const string CONFIG_PARAM_NODE_NAME = "parameters"; static const string CAPAB_NODE_NAME = "capabilities"; +static const string RECONFIG_NODE_NAME = "reconfiguration"; static const string FIXED_FLOW_NODE_NAME = "fixedflow"; @@ -72,9 +73,13 @@ void YamlToXMLConverter::parseYamlFile() { parseCapabInfo(value); } + else if(nodeName == RECONFIG_NODE_NAME) + { + parseReconfigurationInfo(value); + } else { - std::string msg = "Node's name is unknow to us."; + std::string msg = "Node's name is unknown to us."; YAML::ParserException e(YAML::Mark::null_mark(), msg); throw e; } @@ -102,7 +107,8 @@ void YamlToXMLConverter::parseYamlFile() string nodeName = key.as(); if(nodeName == AE_NODE_NAME) { - genAEInfo(value); + parseAnnotatorInfo(value); + //genAEInfo(value); } else if(rs::common::getAnnotatorPath(nodeName) != "") { @@ -185,7 +191,7 @@ string YamlToXMLConverter::getType(const YAML::Node &node) } -bool YamlToXMLConverter::genAEInfo(const YAML::Node &node) +/*bool YamlToXMLConverter::genAEInfo(const YAML::Node &node) { if(node.Type() == YAML::NodeType::Map) { @@ -213,8 +219,9 @@ bool YamlToXMLConverter::genAEInfo(const YAML::Node &node) } return true; -} +}*/ +// TODO: Why two equal functions? bool YamlToXMLConverter::parseAnnotatorInfo(const YAML::Node &node) { if(node.Type() == YAML::NodeType::Map) @@ -638,10 +645,9 @@ bool YamlToXMLConverter::genCapabInfo(const YAML::Node &node) return true; } -bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string annotator_name) -{ - rs::AnnotatorCapabilities annotCap; +bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string annotator_name, std::string setup_name) +{ annotCap.annotatorName = annotator_name; if(node.Type() == YAML::NodeType::Map) { @@ -663,7 +669,16 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno if(sit->Type() == YAML::NodeType::Scalar) { std::string val = sit->as(); - annotCap.iTypeValueRestrictions[val] = std::vector(); + if(setup_name.empty()) + { + annotCap.iTypeValueRestrictions[val] = std::vector(); + } + else + { + ostringstream id; + id << setup_name << ":" << val; + annotCap.rInputTypeValueRestrictions[id.str()] = std::vector(); + } } if(sit->Type() == YAML::NodeType::Map) { @@ -674,13 +689,23 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno { if(e.second.Type() == YAML::NodeType::Sequence) { - annotCap.iTypeValueRestrictions[e.first.as()] = e.second.as>(); + string val = e.first.as(); + if(setup_name.empty()) + { + annotCap.iTypeValueRestrictions[val] = e.second.as>(); + } + else + { + ostringstream id; + id << setup_name << ":" << val; + annotCap.rInputTypeValueRestrictions[id.str()] = e.second.as>(); + } } } } else { - outError("Inpute Type value restriction needs to be a single map entry;"); + outError("Input Type value restriction needs to be a single map entry;"); return false; } } @@ -702,7 +727,15 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno if(n.Type() == YAML::NodeType::Scalar) { std::string val = n.as(); - annotCap.oTypeValueDomains[val] = std::vector(); + if(setup_name.empty()){ + annotCap.oTypeValueDomains[val] = std::vector(); + } + else + { + ostringstream id; + id << setup_name << ":" << val; + annotCap.rOutputTypeValueDomains[id.str()] = std::vector(); + } } if(n.Type() == YAML::NodeType::Map) { @@ -713,8 +746,16 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno { if(e.second.Type() == YAML::NodeType::Sequence) { - std::vector listValue = e.second.as>(); - annotCap.oTypeValueDomains[e.first.as()] = e.second.as>(); + string val = e.first.as(); + if(setup_name.empty()){ + annotCap.oTypeValueDomains[val] = e.second.as>(); + } + else + { + ostringstream id; + id << setup_name << ":" << val; + annotCap.rOutputTypeValueDomains[id.str()] = e.second.as>(); + } } } } @@ -784,3 +825,43 @@ std::vector YamlToXMLConverter::getOverwrittenAnnotat { return overwrittenAnnotCaps; } + +bool YamlToXMLConverter::parseReconfigurationInfo(const YAML::Node &node) +{ + for(YAML::const_iterator it = node.begin(); it != node.end(); ++it) + { + string setup_name = it->first.as(); + + for(YAML::const_iterator sit = it->second.begin(); sit != it->second.end(); ++sit) + { + if(sit->first.Type() == YAML::NodeType::Scalar) + { + string node_name = sit->first.as(); + + if(node_name == CAPAB_NODE_NAME) + { + parseCapabInfo(sit->second, "", setup_name); + } + else if(node_name == CONFIG_PARAM_NODE_NAME) + { + // TODO: Also save params for reconfiguration? + } + else + { + string msg = "Node's name is unknown to us."; + YAML::ParserException e(YAML::Mark::null_mark(), msg); + throw e; + } + } + else + { + std::string msg = "Node's key should be scalar."; + YAML::ParserException e(YAML::Mark::null_mark(), msg); + throw e; + } + } + } + + return true; +} + diff --git a/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h index c6ed3dc1..5e9108d3 100644 --- a/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h +++ b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h @@ -169,6 +169,8 @@ class KnowledgeEngine outDebug(individualOfAnnotator); std::map> inputRestrictions = annotatorData.second.iTypeValueRestrictions; std::map> outputDomains = annotatorData.second.oTypeValueDomains; + std::map> reconfigInputRestrictions = annotatorData.second.rInputTypeValueRestrictions; + std::map> reconfigOutputDomains = annotatorData.second.rOutputTypeValueDomains; if(!inputRestrictions.empty()) { @@ -239,6 +241,20 @@ class KnowledgeEngine } } } + + if(!reconfigInputRestrictions.empty()) { + // TODO: Add assertations regarding to input restriction reconfiguration + } + + if(!reconfigOutputDomains.empty()) { + outInfo(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>"); + + for(auto e : reconfigOutputDomains){ + if(!e.second.empty()) + outInfo(e.first << " <==> " << e.second[0]); + } + outInfo(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>"); + } } } else From 6f91dd155ae3a5ffa0eaca42a42281f943a00226 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Sun, 29 Mar 2020 20:05:52 +0200 Subject: [PATCH 02/13] Original demo --- robosherlock/descriptors/analysis_engines/demo.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/robosherlock/descriptors/analysis_engines/demo.yaml b/robosherlock/descriptors/analysis_engines/demo.yaml index f5edd174..5027b02b 100644 --- a/robosherlock/descriptors/analysis_engines/demo.yaml +++ b/robosherlock/descriptors/analysis_engines/demo.yaml @@ -9,6 +9,5 @@ fixedflow: - ImageSegmentationAnnotator - PointCloudClusterExtractor - ClusterMerger - - SacModelAnnotator CollectionReader: camera_config_files: ['config_kinect_robot.ini'] From aaa71d761428b3239215ebe7bdef1f687731c8de Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Sun, 29 Mar 2020 20:06:52 +0200 Subject: [PATCH 03/13] SacModelAnnotator: changed model value type to string --- .../annotation/SacModelAnnotator.yaml | 4 +-- .../src/annotation/src/SacModelAnnotator.cpp | 34 +++++++------------ 2 files changed, 14 insertions(+), 24 deletions(-) diff --git a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml index 7b8893d5..dac378ee 100644 --- a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml +++ b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml @@ -21,7 +21,7 @@ parameters: minPoints: 200 radiusLimit1: 0.01 radiusLimit2: 0.5 - sacModel: 5 + sacModel: Cylinder useNormals: true reconfiguration: @@ -35,7 +35,7 @@ reconfiguration: # Overwrite or define new parameters: parameters: test_param: "success" - sacModel: 4 + sacModel: Sphere # Example setup setup_example: diff --git a/robosherlock/src/annotation/src/SacModelAnnotator.cpp b/robosherlock/src/annotation/src/SacModelAnnotator.cpp index 96ce75c6..6e095eab 100644 --- a/robosherlock/src/annotation/src/SacModelAnnotator.cpp +++ b/robosherlock/src/annotation/src/SacModelAnnotator.cpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include @@ -35,7 +36,6 @@ #include #include -#include #define DEBUG_OUTPUT 0 using namespace uima; @@ -51,30 +51,20 @@ class SacModelAnnotator : public Annotator TyErrorId readParameters(AnnotatorContext &ctx) { if(ctx.isParameterDefined("sacModel")) { - int selectedModel; - ctx.extractValue("sacModel", selectedModel); - - switch(selectedModel) { - case pcl::SACMODEL_CYLINDER: // 5 - name = "CYLINDER"; - break; - case pcl::SACMODEL_SPHERE: // 4 - name = "SPHERE"; - break; - case pcl::SACMODEL_CIRCLE2D: // 2 - name = "CIRCLE"; - break; - case pcl::SACMODEL_PLANE: // 0 - name = "PLANE"; - break; - - default: - return UIMA_ERR_NOT_YET_IMPLEMENTED; + ctx.extractValue("sacModel", name); + std::transform(name.begin(), name.end(), name.begin(), ::toupper); + + if(name == "CYLINDER"){ + sacModel = pcl::SACMODEL_CYLINDER; + } + else if(name == "SPHERE"){ + sacModel = pcl::SACMODEL_NORMAL_SPHERE; + } + else{ + return UIMA_ERR_NOT_YET_IMPLEMENTED; } - sacModel = static_cast(selectedModel); outInfo("Selected " << name << " (" << sacModel << ").."); - return UIMA_ERR_NONE; } From e3bb806671738e76423d9b813e31690eaec82718 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Sun, 26 Apr 2020 14:54:59 +0200 Subject: [PATCH 04/13] Prolog rules and service definitions --- .../analysis_engines/reconfig_demo.yaml | 14 ++ robosherlock/prolog/rs_query_reasoning.pl | 150 ++++++++++++++---- .../flowcontrol/RSProcessManager.h | 6 + .../flowcontrol/YamlToXMLConverter.h | 3 - .../src/flowcontrol/src/RSProcessManager.cpp | 14 +- robosherlock_msgs/CMakeLists.txt | 2 + robosherlock_msgs/srv/OverwriteParam.srv | 27 ++++ .../srv/ReconfigureAnnotator.srv | 4 + 8 files changed, 182 insertions(+), 38 deletions(-) create mode 100644 robosherlock/descriptors/analysis_engines/reconfig_demo.yaml create mode 100644 robosherlock_msgs/srv/OverwriteParam.srv create mode 100644 robosherlock_msgs/srv/ReconfigureAnnotator.srv diff --git a/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml new file mode 100644 index 00000000..f5edd174 --- /dev/null +++ b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml @@ -0,0 +1,14 @@ +ae: + name: demo +fixedflow: + - CollectionReader + - ImagePreprocessor + - PointCloudFilter + - NormalEstimator + - PlaneAnnotator + - ImageSegmentationAnnotator + - PointCloudClusterExtractor + - ClusterMerger + - SacModelAnnotator +CollectionReader: + camera_config_files: ['config_kinect_robot.ini'] diff --git a/robosherlock/prolog/rs_query_reasoning.pl b/robosherlock/prolog/rs_query_reasoning.pl index 77d18d3b..4eb31790 100644 --- a/robosherlock/prolog/rs_query_reasoning.pl +++ b/robosherlock/prolog/rs_query_reasoning.pl @@ -42,7 +42,10 @@ retract_query_lang/0, assert_test_case/0, retract_all_annotators/0, - retract_query_assertions/0 + retract_query_assertions/0, + + set_annotator_setup_names/2, + assert_reconfiguration_pipeline/0 ]). :- rdf_meta @@ -67,7 +70,7 @@ compute_annotators(A) :- - owl_subclass_of(A,rs_components:'RoboSherlockComponent'), + owl_subclass_of(A,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), not(A = 'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), not(A = 'http://knowrob.org/kb/rs_components.owl#AnnotationComponent'), not(A = 'http://knowrob.org/kb/rs_components.owl#DetectionComponent'), @@ -82,28 +85,28 @@ % assert domain restriction for an individual generated from a RoboSherlockComponents set_annotator_domain(AnnotatorI, Domain):- - owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), - owl_restriction_assert(restriction(rs_components:'outputDomain',all_values_from(union_of(Domain))),R), + owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + owl_restriction_assert(restriction('http://knowrob.org/kb/rs_components.owl#outputDomain',all_values_from(union_of(Domain))),R), rdf_assert(AnnotatorI,rdf:type,R). %%%% set a domain constraint on the type of the annotator e.g. Primitive Shape annotator returns Shape annotations with value one of [a,b,c] %%%% set_annotator_output_type_domain(AnnotatorI, Domain, Type):- - owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), + owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_outputs(Annotator, Type),%% you can only set this restriction if the Type is defined as an output type owl_restriction_assert(restriction(Type,all_values_from(union_of(Domain))),R), rdf_assert(AnnotatorI,rdf:type,R). set_annotator_input_type_constraint(AnnotatorI, Constraint, Type):- - owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), + owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_inputs(Annotator, Type),%% you can only set this restriction if the Type is defined as an output type owl_restriction_assert(restriction(Type,all_values_from(union_of(Constraint))),R), rdf_assert(AnnotatorI,rdf:type,R). compute_annotator_output_type_domain(AnnotatorI, Type, Domain):- - owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), + owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_outputs(Annotator, Type), owl_has(AnnotatorI,rdf:type,R), @@ -111,7 +114,7 @@ rdf_has(R,owl:allValuesFrom,V),owl_description(V,union_of(Domain)). compute_annotator_input_type_restriction(AnnotatorI, Type, Domain):- - owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), + owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_inputs(Annotator, Type), owl_has(AnnotatorI,rdf:type,R), @@ -123,13 +126,13 @@ compute_annotator_outputs(Annotator,Output) :- annotators(Annotator), owl_has(Annotator,rdfs:subClassOf, O), - owl_restriction(O, restriction(rs_components:'perceptualOutput',some_values_from(Output))). + owl_restriction(O, restriction('http://knowrob.org/kb/rs_components.owl#perceptualOutput',some_values_from(Output))). % Get inputs of Annotator compute_annotator_inputs(Annotator,Input) :- annotators(Annotator), owl_has(Annotator,rdfs:subClassOf,O), - owl_restriction(O, restriction(rs_components:'perceptualInputRequired',some_values_from(Input))). + owl_restriction(O, restriction('http://knowrob.org/kb/rs_components.owl#perceptualInputRequired',some_values_from(Input))). % cache outputs/inputs :- forall(compute_annotator_outputs(A,O), assert(annotator_outputs(A,O)) ). @@ -354,24 +357,24 @@ build_pipeline(Annotators, Pipeline). assert_test_pipeline:- - kb_create(rs_components:'CollectionReader',_),kb_create(rs_components:'ImagePreprocessor',_), - kb_create(rs_components:'RegionFilter',_), - kb_create(rs_components:'NormalEstimator',_), - kb_create(rs_components:'PlaneAnnotator',_), - kb_create(rs_components:'ImageSegmentationAnnotator',_), - kb_create(rs_components:'PointCloudClusterExtractor',_), - kb_create(rs_components:'ClusterMerger',_), - kb_create(rs_components:'Cluster3DGeometryAnnotator',GI),set_annotator_output_type_domain(GI,[rs_components:'Small',rs_components:'Big',rs_components:'Medium'],rs_components:'RsAnnotationGeometry'), - kb_create(rs_components:'PrimitiveShapeAnnotator',PI),set_annotator_output_type_domain(PI,[rs_components:'Box',rs_components:'Round'],rs_components:'RsAnnotationShape'), - kb_create(rs_components:'ClusterColorHistogramCalculator',CI),set_annotator_output_type_domain(CI,[rs_components:'Yellow',rs_components:'Blue'],rs_components:'RsAnnotationSemanticcolor'), - kb_create(rs_components:'SacModelAnnotator',SI),set_annotator_output_type_domain(SI,[rs_components:'Cylinder'],rs_components:'RsAnnotationShape'), - kb_create(rs_components:'PCLDescriptorExtractor',_), - kb_create(rs_components:'CaffeAnnotator',_), - kb_create(rs_components:'KnnAnnotator',KNNI),set_annotator_output_type_domain(KNNI,[kitchen:'WhiteCeramicIkeaBowl', kitchen:'KoellnMuesliKnusperHonigNuss'], rs_components:'RsAnnotationClassification'), - kb_create(rs_components:'HandleAnnotator',HI),set_annotator_output_type_domain(HI,[rs_components:'Handle'], rs_components:'RsAnnotationDetection'). - + kb_create('http://knowrob.org/kb/rs_components.owl#CollectionReader',_),kb_create('http://knowrob.org/kb/rs_components.owl#ImagePreprocessor',_), + kb_create('http://knowrob.org/kb/rs_components.owl#RegionFilter',_), + kb_create('http://knowrob.org/kb/rs_components.owl#NormalEstimator',_), + kb_create('http://knowrob.org/kb/rs_components.owl#PlaneAnnotator',_), + kb_create('http://knowrob.org/kb/rs_components.owl#ImageSegmentationAnnotator',_), + kb_create('http://knowrob.org/kb/rs_components.owl#PointCloudClusterExtractor',_), + kb_create('http://knowrob.org/kb/rs_components.owl#ClusterMerger',_), + kb_create('http://knowrob.org/kb/rs_components.owl#Cluster3DGeometryAnnotator',GI),set_annotator_output_type_domain(GI,['http://knowrob.org/kb/rs_components.owl#Small','http://knowrob.org/kb/rs_components.owl#Big','http://knowrob.org/kb/rs_components.owl#Medium'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationGeometry'), + kb_create('http://knowrob.org/kb/rs_components.owl#PrimitiveShapeAnnotator',PI),set_annotator_output_type_domain(PI,['http://knowrob.org/kb/rs_components.owl#Box','http://knowrob.org/kb/rs_components.owl#Round'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape'), + kb_create('http://knowrob.org/kb/rs_components.owl#ClusterColorHistogramCalculator',CI),set_annotator_output_type_domain(CI,['http://knowrob.org/kb/rs_components.owl#Yellow','http://knowrob.org/kb/rs_components.owl#Blue'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationSemanticcolor'), + kb_create('http://knowrob.org/kb/rs_components.owl#SacModelAnnotator',SI),set_annotator_output_type_domain(SI,['http://knowrob.org/kb/rs_components.owl#Cylinder'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape'), + kb_create('http://knowrob.org/kb/rs_components.owl#PCLDescriptorExtractor',_), + kb_create('http://knowrob.org/kb/rs_components.owl#CaffeAnnotator',_), + kb_create('http://knowrob.org/kb/rs_components.owl#KnnAnnotator',KNNI),set_annotator_output_type_domain(KNNI,[kitchen:'WhiteCeramicIkeaBowl', kitchen:'KoellnMuesliKnusperHonigNuss'], 'http://knowrob.org/kb/rs_components.owl#RsAnnotationClassification'), + kb_create('http://knowrob.org/kb/rs_components.owl#HandleAnnotator',HI),set_annotator_output_type_domain(HI,['http://knowrob.org/kb/rs_components.owl#Handle'], 'http://knowrob.org/kb/rs_components.owl#RsAnnotationDetection'). + assert_query:- - assert(requestedValueForKey(shape,rs_components:'Box')). + assert(requestedValueForKey(shape,'http://knowrob.org/kb/rs_components.owl#Box')). assert_query_lang:- assert(rs_query_predicate(shape)), @@ -388,12 +391,12 @@ assert(rs_query_predicate(timestamp)), assert(rs_query_predicate(location)), assert(rs_query_predicate(has-ingredient)), - rdf_global_id(rs_components:'RsAnnotationShape',A),assert(rs_type_for_predicate(shape, A)), - rdf_global_id(rs_components:'RsAnnotationSemanticcolor',B),assert(rs_type_for_predicate(color, B)), - rdf_global_id(rs_components:'RsAnnotationGeometry',C), - rdf_global_id(rs_components:'RsAnnotationDetection',D), - rdf_global_id(rs_components:'RsAnnotationClassification',E), - rdf_global_id(rs_components:'RsAnnotationPose',F), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationShape',A),assert(rs_type_for_predicate(shape, A)), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationSemanticcolor',B),assert(rs_type_for_predicate(color, B)), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationGeometry',C), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationDetection',D), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationClassification',E), + rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationPose',F), assert(rs_type_for_predicate(size, C)), assert(rs_type_for_predicate(detection, D)), assert(rs_type_for_predicate(class, E)), @@ -416,9 +419,88 @@ retractall(rs_type_for_predicate(_,_)). retract_all_annotators:- - forall(owl_subclass_of(S,rs_components:'RoboSherlockComponent'), + forall(owl_subclass_of(S,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), rdf_retractall(_,rdf:type,S)). retract_query_assertions:- retract(requestedValueForKey(_,_)). +%% Reconfiguration Rules + +assert_reconfiguration_pipeline:- + assert_test_pipeline, + owl_individual_of(I, 'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + set_annotator_setup_names(I, ['SetupCylinder', 'SetupSphere']), + set_annotator_setup_output_type_domain(I, 'SetupCylinder', 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Cylinder']), + set_annotator_setup_output_type_domain(I, 'SetupSphere', 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Sphere']), + set_annotator_setup_input_type_constraint(I, 'SetupSphere', 'http://knowrob.org/kb/rs_components.owl#perceptualInputRequired', ['http://knowrob.org/kb/rs_components.owl#RsSceneMergedhypothesis'] ). + + +set_annotator_setup_names(AnnotatorI, Setups) :- + foreach(member(Setup, Setups), + assert(annotator_setup_names(AnnotatorI, Setup))). + +set_annotator_setup_output_type_domain(AnnotatorI, Setup, Type, Domain) :- + annotator_setup_names(AnnotatorI, Setup), %% check if setup exists + assert(annotator_setup_output_type((AnnotatorI, Setup), Type)), + assert(annotator_setup_output_domain((AnnotatorI, Setup), Domain)). + +set_annotator_setup_input_type_constraint(AnnotatorI, Setup, Type, Constraint) :- + annotator_setup_names(AnnotatorI, Setup), %% check if setup exists + assert(annotator_setup_input_type((AnnotatorI, Setup), Type)), + assert(annotator_setup_input_constraint((AnnotatorI, Setup), Constraint)). + +set_annotator_setup_parameter(AnnotatorI, Setup, Parameter, Value) :- + annotator_setup_names(AnnotatorI, Setup), %% check if setup exists + assert(annotator_setup_parameter((AnnotatorI, Setup), [Parameter, Value])). + + +load_annotator_setup(AnnotatorI, Setup) :- + annotator_setup_names(AnnotatorI, Setup), %% check if setup exists + %% Update output and input + load_annotator_setup_input(AnnotatorI, Setup), + load_annotator_setup_output(AnnotatorI, Setup). + %% TODO: Call Cpp Rule to reconfigure annotator + +load_annotator_setup_input(AnnotatorI, Setup) :- + annotator_setup_input_type((AnnotatorI, Setup), Type), + annotator_setup_input_constraint((AnnotatorI, Setup), Constraint), + write(Type),nl,write(Constraint),nl, + %% TODO: retract old input + set_annotator_input_type_constraint(AnnotatorI, Constraint, Type). + +load_annotator_setup_output(AnnotatorI, Setup) :- + annotator_setup_output_type((AnnotatorI, Setup), Type), + annotator_setup_output_domain((AnnotatorI, Setup), Domain), + write('Annotator: '),writeln(AnnotatorI), + write('Domain: '),writeln(Domain), + write('Type: '),writeln(Type), + %% TODO: retract old output + set_annotator_output_type_domain(AnnotatorI, Domain, Type). + +load_annotator_setup_parameter(AnnotatorI, Setup, Parameter, Value) :- + annotator_setup_names(AnnotatorI, Setup), %% check if setup exists + annotator_setup_parameter((AnnotatorI, Setup), Parameter, Value). + %% TODO: Overwrite param with Cpp Rule + + +find_annotator_setup_for_output_type_domain(AnnotatorI, Setup, Type, Domain) :- + annotator_setup_output_type((AnnotatorI, Setup), Type), + annotator_setup_output_domain((AnnotatorI, Setup), Domain). + +find_annotator_setup_for_input_type_constraint(AnnotatorI, Setup, Type, Constraint) :- + annotator_setup_input_type((AnnotatorI, Setup), Type), + annotator_setup_input_constraint((AnnotatorI, Setup), Constraint). + + +%% TEST TODO: REMOVE +find_sphere_setup(A, S) :- + find_annotator_setup_for_output_type_domain(A, S, 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Sphere']). + +load_sphere_setup:- + owl_individual_of(I,'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + load_annotator_setup_output(I, 'SetupSphere'). + +load_cylinder_setup:- + owl_individual_of(I,'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + load_annotator_setup(I, 'SetupCylinder'). \ No newline at end of file diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h index 05d6ddd5..64cf557b 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h @@ -159,6 +159,12 @@ class RSProcessManager */ bool reconfigureAnnotator(std::string &annotatorName); + bool handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, + robosherlock_msgs::ReconfigureAnnotator::Respone &res); + + bool handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, + robosherlock_msgs::OverwriteParam::Response &res); + /** * @brief setUseIdentityResolution run identiy resolution for tracking objects over multiple scenes * @param useIdentityResoltuion diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h index 392c42de..4831ed8b 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h @@ -126,9 +126,6 @@ class YamlToXMLConverter string getType(const YAML::Node& node); string getTypeFilePath() const; - // TODO: Why identical function implementation? - //bool genAEInfo(const YAML::Node& node); - bool parseAnnotatorInfo(const YAML::Node& node); bool generateAnnotatorConfigParamInfo(const YAML::Node& node); diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index e1a80167..2fa735e8 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -24,7 +24,7 @@ RSProcessManager::RSProcessManager(std::string engineFile, const bool useVisuali if(ros::service::waitForService("rosprolog/query", ros::Duration(60.0))) knowledge_engine_ = std::make_shared(); else - throw rs::Exception("rosprolog client sercivice not reachable"); + throw rs::Exception("rosprolog client service not reachable"); #else throw rs::Exception("rosprolog was not found at compile time!"); #endif @@ -46,6 +46,7 @@ RSProcessManager::RSProcessManager(std::string engineFile, const bool useVisuali setFlowService_ = nh_.advertiseService("execute_pipeline", &RSProcessManager::executePipelineCallback, this); queryService_ = nh_.advertiseService("query", &RSProcessManager::jsonQueryCallback, this); + // ROS publisher declarations result_pub_ = nh_.advertise(std::string("result_advertiser"), 1); image_pub_ = it_.advertise("result_image", 1, true); @@ -585,6 +586,17 @@ bool RSProcessManager::reconfigureAnnotator(std::string &annotatorName) { return reconfigureAnnotator(engine_->getIndexOfAnnotator(std::move(annotatorName))); } +bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, + robosherlock_msgs::ReconfigureAnnotator::Respone &res) { + req. + return false; +} + +bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::ReconfigureAnnotator::Request &req, + robosherlock_msgs::ReconfigureAnnotator::Respone &res) { + return false; +} + template bool RSProcessManager::drawResultsOnImage(const std::vector &filter, const std::vector &resultDesignators, std::string &requestJson, cv::Mat &resImage); diff --git a/robosherlock_msgs/CMakeLists.txt b/robosherlock_msgs/CMakeLists.txt index 447f99ff..0191fc53 100644 --- a/robosherlock_msgs/CMakeLists.txt +++ b/robosherlock_msgs/CMakeLists.txt @@ -23,6 +23,8 @@ add_service_files(FILES RSVisControl.srv UpdateObjects.srv ExecutePipeline.srv + OverwriteParam.srv + ReconfigureAnnotator.srv ) add_action_files(DIRECTORY action FILES RSQuery.action) diff --git a/robosherlock_msgs/srv/OverwriteParam.srv b/robosherlock_msgs/srv/OverwriteParam.srv new file mode 100644 index 00000000..4aae7ca4 --- /dev/null +++ b/robosherlock_msgs/srv/OverwriteParam.srv @@ -0,0 +1,27 @@ +string annotatorName +string parameterName +uint8 parameterType + +int32 parameterInteger +float64 parameterFloat +string parameterString +bool parameterBool + +int32[] parameterIntegerVector +float64[] parameterFloatVector +string[] parameterStringVector +bool[] parameterBoolVector + +--- +bool result + + +# Parameter Types: +uint8 INT = 0 +uint8 FLOAT = 1 +uint8 STRING = 2 +uint8 BOOl = 3 +uint8 INT_VECTOR = 4 +uint8 FLOAT_VECTOR = 5 +uint8 STRING_VECTOR = 6 +uint8 BOOL_VECTOR = 7 diff --git a/robosherlock_msgs/srv/ReconfigureAnnotator.srv b/robosherlock_msgs/srv/ReconfigureAnnotator.srv new file mode 100644 index 00000000..b8e0fd01 --- /dev/null +++ b/robosherlock_msgs/srv/ReconfigureAnnotator.srv @@ -0,0 +1,4 @@ +string annotatorName +string setupName +--- +bool result From 6fe61b315736b3360480dc15a919ea3c91325165 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 28 Apr 2020 20:50:59 +0200 Subject: [PATCH 05/13] Moved reconfigure methods to RSAggregateAnalysisEngine --- .../flowcontrol/RSAggregateAnalysisEngine.h | 15 +++++++++++++++ .../robosherlock/flowcontrol/RSProcessManager.h | 13 ------------- .../flowcontrol/src/RSAggregateAnalysisEngine.cpp | 13 +++++++++++++ .../src/flowcontrol/src/RSProcessManager.cpp | 14 +------------- 4 files changed, 29 insertions(+), 26 deletions(-) diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h index 74879435..657d839a 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h @@ -325,6 +325,21 @@ class RSAggregateAnalysisEngine : public uima::internal::AggregateEngine cr_context->assignValue(UnicodeString(param_name.c_str()), conversionString); } + /** + * @brief RSProcessManager::resetAE reset analysis engine that was instantiated; Use this method i + * if you want to change the AAE loaded at startup + * @param newAAEName name of the new aggregate analysis engine; + * @return true/false + */ + bool resetAE(std::string); + + /** + * @brief Reconfigures a single annotator + * @param annotatorIdx Index of annotator in pipeline + * @return true on success + */ + bool reconfigureAnnotator(int annotatorIdx); + // this variable is for fail safe mechanism to fall back to linear execution if query orderings fail bool querySuccess; diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h index 64cf557b..f48804a8 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h @@ -137,20 +137,7 @@ class RSProcessManager */ bool virtual handleQuery(std::string &req, std::vector &res); - /** - * @brief RSProcessManager::resetAE reset analysis engine that was instantiated; Use this method i - * if you want to change the AAE loaded at startup - * @param newAAEName name of the new aggregate analysis engine; - * @return true/false - */ - bool resetAE(std::string); - /** - * @brief Reconfigures a single annotator - * @param annotatorIdx Index of annotator in pipeline - * @return true on success - */ - bool reconfigureAnnotator(int annotatorIdx); /** * @brief Reconfigures a single annotator diff --git a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp index deb3eaf4..67f9734e 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -642,4 +642,17 @@ RSAggregateAnalysisEngine* createParallelAnalysisEngine(uima::AnnotatorContext& } return NULL; } + +bool RSProcessManager::reconfigureAnnotator(int annotatorIdx) { + if(annotatorIdx >= 0 && annotatorIdx < engine_->iv_annotatorMgr.iv_vecEntries.size()) { + return engine_->iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; + } + + return false; +} + +bool RSProcessManager::reconfigureAnnotator(std::string &annotatorName) { + return reconfigureAnnotator(engine_->getIndexOfAnnotator(std::move(annotatorName))); +} + } // namespace rs diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 2fa735e8..72f4201f 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -574,25 +574,13 @@ bool RSProcessManager::highlightResultsInCloud(const std::vector &filter, return true; } -bool RSProcessManager::reconfigureAnnotator(int annotatorIdx) { - if(annotatorIdx >= 0 && annotatorIdx < engine_->iv_annotatorMgr.iv_vecEntries.size()) { - return engine_->iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; - } - - return false; -} - -bool RSProcessManager::reconfigureAnnotator(std::string &annotatorName) { - return reconfigureAnnotator(engine_->getIndexOfAnnotator(std::move(annotatorName))); -} - bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, robosherlock_msgs::ReconfigureAnnotator::Respone &res) { req. return false; } -bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::ReconfigureAnnotator::Request &req, +bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam:: &req, robosherlock_msgs::ReconfigureAnnotator::Respone &res) { return false; } From 18422053e0f4011f630187153203a2426a5e4812 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 28 Apr 2020 22:27:56 +0200 Subject: [PATCH 06/13] Fixed copyPasta, removed duplicated code --- .../flowcontrol/RSAggregateAnalysisEngine.h | 13 ++--- .../flowcontrol/RSProcessManager.h | 17 +++--- .../src/RSAggregateAnalysisEngine.cpp | 25 ++++----- .../src/flowcontrol/src/RSProcessManager.cpp | 56 ++++++++++++++++--- .../flowcontrol/src/YamlToXMLConverter.cpp | 32 ----------- 5 files changed, 76 insertions(+), 67 deletions(-) diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h index 657d839a..c059eafa 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h @@ -326,19 +326,18 @@ class RSAggregateAnalysisEngine : public uima::internal::AggregateEngine } /** - * @brief RSProcessManager::resetAE reset analysis engine that was instantiated; Use this method i - * if you want to change the AAE loaded at startup - * @param newAAEName name of the new aggregate analysis engine; - * @return true/false + * @brief Reconfigures a single annotator + * @param annotatorIdx Index of annotator in pipeline + * @return true on success */ - bool resetAE(std::string); + bool reconfigureAnnotator(int annotatorIdx); /** * @brief Reconfigures a single annotator - * @param annotatorIdx Index of annotator in pipeline + * @param annotatorName Name of annotator in pipeline * @return true on success */ - bool reconfigureAnnotator(int annotatorIdx); + bool reconfigureAnnotator(std::string &annotatorName); // this variable is for fail safe mechanism to fall back to linear execution if query orderings fail diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h index f48804a8..cf32cb9f 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSProcessManager.h @@ -12,6 +12,8 @@ #include #include #include +#include +#include #include @@ -58,7 +60,7 @@ class RSProcessManager ros::AsyncSpinner spinner_; - ros::ServiceServer setContextService_, queryService_, setFlowService_; + ros::ServiceServer setContextService_, queryService_, setFlowService_, reconfigureService_, overwriteParamService_; ros::Publisher result_pub_; ros::Publisher pc_pub_; image_transport::Publisher image_pub_; @@ -137,17 +139,16 @@ class RSProcessManager */ bool virtual handleQuery(std::string &req, std::vector &res); - - /** - * @brief Reconfigures a single annotator - * @param annotatorName Name of annotator in pipeline - * @return true on success + * @brief RSProcessManager::resetAE reset analysis engine that was instantiated; Use this method i + * if you want to change the AAE loaded at startup + * @param newAAEName name of the new aggregate analysis engine; + * @return true/false */ - bool reconfigureAnnotator(std::string &annotatorName); + bool resetAE(std::string); bool handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, - robosherlock_msgs::ReconfigureAnnotator::Respone &res); + robosherlock_msgs::ReconfigureAnnotator::Response &res); bool handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, robosherlock_msgs::OverwriteParam::Response &res); diff --git a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp index 67f9734e..efd8beb8 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -366,6 +366,18 @@ void RSAggregateAnalysisEngine::setPipelineOrdering(std::vector ann } } +bool RSAggregateAnalysisEngine::reconfigureAnnotator(int annotatorIdx) { + if(annotatorIdx >= 0 && annotatorIdx < iv_annotatorMgr.iv_vecEntries.size()) { + return iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; + } + + return false; +} + +bool RSAggregateAnalysisEngine::reconfigureAnnotator(std::string &annotatorName) { + return reconfigureAnnotator(getIndexOfAnnotator(std::move(annotatorName))); +} + namespace rs { std::string convertAnnotatorYamlToXML(std::string annotator_name, @@ -642,17 +654,4 @@ RSAggregateAnalysisEngine* createParallelAnalysisEngine(uima::AnnotatorContext& } return NULL; } - -bool RSProcessManager::reconfigureAnnotator(int annotatorIdx) { - if(annotatorIdx >= 0 && annotatorIdx < engine_->iv_annotatorMgr.iv_vecEntries.size()) { - return engine_->iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; - } - - return false; -} - -bool RSProcessManager::reconfigureAnnotator(std::string &annotatorName) { - return reconfigureAnnotator(engine_->getIndexOfAnnotator(std::move(annotatorName))); -} - } // namespace rs diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 72f4201f..88332c78 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -45,7 +45,8 @@ RSProcessManager::RSProcessManager(std::string engineFile, const bool useVisuali setContextService_ = nh_.advertiseService("set_context", &RSProcessManager::resetAECallback, this); setFlowService_ = nh_.advertiseService("execute_pipeline", &RSProcessManager::executePipelineCallback, this); queryService_ = nh_.advertiseService("query", &RSProcessManager::jsonQueryCallback, this); - + reconfigureService_ = nh_.advertiseService("reconfigure_annotator", &RSProcessManager::handleReconfigureAnnotator, this); + overwriteParamService_ = nh_.advertiseService("overwrite_param", &RSProcessManager::handleOverwriteParam, this); // ROS publisher declarations result_pub_ = nh_.advertise(std::string("result_advertiser"), 1); @@ -575,14 +576,55 @@ bool RSProcessManager::highlightResultsInCloud(const std::vector &filter, } bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, - robosherlock_msgs::ReconfigureAnnotator::Respone &res) { - req. - return false; + robosherlock_msgs::ReconfigureAnnotator::Response &res) { + if(req.setupName.empty()) { + // No setup provided; reconfigure only. + outInfo("No setup name provided, just calling reconfigure() now."); + engine_->reconfigureAnnotator(req.annotatorName); + } + else { + + } + return true; } -bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam:: &req, - robosherlock_msgs::ReconfigureAnnotator::Respone &res) { - return false; +bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, + robosherlock_msgs::OverwriteParam::Response &res) { + switch(req.parameterType) { + case robosherlock_msgs::OverwriteParamRequest::INT: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterInteger); + break; + case robosherlock_msgs::OverwriteParamRequest::INT_VECTOR: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterIntegerVector); + break; + case robosherlock_msgs::OverwriteParamRequest::BOOL: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBool); + break; + case robosherlock_msgs::OverwriteParamRequest::BOOL_VECTOR: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBoolVector); + break; + case robosherlock_msgs::OverwriteParamRequest::FLOAT: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterFloat); + break; + case robosherlock_msgs::OverwriteParamRequest::FLOAT_VECTOR: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterFloatVector); + break; + case robosherlock_msgs::OverwriteParamRequest::STRING: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterString); + break; + case robosherlock_msgs::OverwriteParamRequest::STRING_VECTOR: + engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterStringVector); + break; + + default: + outError("Invalid data type in OverwriteParam Service Request."); + res.result = false; + return false; + } + + outInfo("OverwriteParam finished successfully."); + res.result = true; + return true; } template bool RSProcessManager::drawResultsOnImage(const std::vector &filter, diff --git a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp index a67caade..5af634dd 100644 --- a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp +++ b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp @@ -190,38 +190,6 @@ string YamlToXMLConverter::getType(const YAML::Node &node) } } - -/*bool YamlToXMLConverter::genAEInfo(const YAML::Node &node) -{ - if(node.Type() == YAML::NodeType::Map) - { - for(YAML::const_iterator mit = node.begin(); mit != node.end(); ++mit) - { - string name = mit->first.as(); - - if(name == "name") - AEName = mit->second.as(); - else if(name == "implementation") - AEImpl = mit->second.as(); - else if(name == "description") - AEDescription = mit->second.as(); - else - { - cerr << mit->second.as() << " is an unknown annotator info to us." << endl; - return false; - } - } - } - else - { - cerr << "Please use map structure under annotator node." << endl; - return false; - } - - return true; -}*/ - -// TODO: Why two equal functions? bool YamlToXMLConverter::parseAnnotatorInfo(const YAML::Node &node) { if(node.Type() == YAML::NodeType::Map) From 2e21eb1b9006c7cca4f6b704c99f76b1b28a7d56 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 28 Apr 2020 22:29:54 +0200 Subject: [PATCH 07/13] Overwrite Parameter Service definition update --- robosherlock_msgs/srv/OverwriteParam.srv | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/robosherlock_msgs/srv/OverwriteParam.srv b/robosherlock_msgs/srv/OverwriteParam.srv index 4aae7ca4..592f1a5d 100644 --- a/robosherlock_msgs/srv/OverwriteParam.srv +++ b/robosherlock_msgs/srv/OverwriteParam.srv @@ -12,16 +12,17 @@ float64[] parameterFloatVector string[] parameterStringVector bool[] parameterBoolVector ---- -bool result - - # Parameter Types: uint8 INT = 0 uint8 FLOAT = 1 uint8 STRING = 2 -uint8 BOOl = 3 +uint8 BOOL = 3 uint8 INT_VECTOR = 4 uint8 FLOAT_VECTOR = 5 uint8 STRING_VECTOR = 6 uint8 BOOL_VECTOR = 7 +--- +bool result + + + From 286f0565328057f669c8a9bf7d5093a72d9a2879 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 28 Apr 2020 22:58:38 +0200 Subject: [PATCH 08/13] OverwriteParamService, ReconfigureService now implemented. --- .../src/flowcontrol/src/RSProcessManager.cpp | 25 +++++++++++++++---- 1 file changed, 20 insertions(+), 5 deletions(-) diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 88332c78..87c76613 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -580,12 +580,24 @@ bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::Reconfigure if(req.setupName.empty()) { // No setup provided; reconfigure only. outInfo("No setup name provided, just calling reconfigure() now."); - engine_->reconfigureAnnotator(req.annotatorName); + res.result = engine_->reconfigureAnnotator(req.annotatorName); } else { - + auto aCaps = engine_->getDelegateAnnotatorCapabilities(); + auto result = aCaps.find(req.annotatorName); + rs::AnnotatorCapabilities aCap; + + if(result != aCaps.end()) { + aCap = result->second; + // TODO: Update input- and output-capabilities here + res.result = true; + } + else { + outError("Annotator " << req.annotatorName << " could not be found."); + res.result = false; + } } - return true; + return res.result; } bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, @@ -601,8 +613,11 @@ bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam::R engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBool); break; case robosherlock_msgs::OverwriteParamRequest::BOOL_VECTOR: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBoolVector); - break; + //engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBoolVector); + // REASON: No valid template-function found during compile-time + outError("Vectors of booleans are currently not supported by the OverwriteParamService."); + res.result = false; + return false; case robosherlock_msgs::OverwriteParamRequest::FLOAT: engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterFloat); break; From 755bb7db434542f1084ac0b71fd78af6d88e4a6a Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 28 Apr 2020 23:51:19 +0200 Subject: [PATCH 09/13] Prolog CPPQueries: reconfigure_annotator, overwrite_param --- .../queryanswering/src/PrologCPPQueries.cpp | 122 ++++++++++++++++++ 1 file changed, 122 insertions(+) diff --git a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp index c2487f7c..cace2c86 100644 --- a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp +++ b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp @@ -5,6 +5,8 @@ #include "robosherlock_msgs/RSQueryService.h" #include "robosherlock_msgs/ExecutePipeline.h" +#include "robosherlock_msgs/ReconfigureAnnotator.h" +#include "robosherlock_msgs/OverwriteParam.h" #include @@ -200,3 +202,123 @@ PREDICATE(write_list, 1) } return TRUE; } + + +/** + * Conversion methods, needed for overwrite_param service calls + */ + +std::vector getIntVector(PlTail prologList) +{ + std::vector result; + PlTerm e; + + while(prologList.next(e)) { + result.push_back(e); + } + + return result; +} + +// ROS FLOAT = DOUBLE! +std::vector getFloatVector(PlTail prologList) +{ + std::vector result; + PlTerm e; + + while(prologList.next(e)) { + result.push_back(*(double *)&e); + } + + return result; +} + +std::vector getStringVector(PlTail prologList) +{ + std::vector result; + PlTerm e; + + while(prologList.next(e)) { + result.push_back(static_cast((char *)e)); + } + return result; +} + + +PREDICATE(cpp_reconfigure_annotator, 2) +{ + std::string *annotatorName, *setupName; + annotatorName = static_cast((void *) PL_A1); + setupName = static_cast((void *) PL_A2); + + ros::NodeHandle n; + ros::ServiceClient client = n.serviceClient("RoboSherlock/reconfigure_annotator"); + robosherlock_msgs::ReconfigureAnnotator srv; + + srv.request.annotatorName = *annotatorName; + srv.request.setupName = *setupName; + + if(client.call(srv)) { + std::cout << "Calling RoboSherlock/reconfigure_annotator was successful" << std::endl; + return TRUE; + } + else { + std::cout << "Calling RoboSherlock/reconfigure_annotator was unsuccessful" << std::endl; + return FALSE; + } +} + + +PREDICATE(cpp_overwrite_param, 4) +{ + std::string *annotatorName, *paramName; + annotatorName = static_cast((void *) PL_A1); + paramName = static_cast((void *) PL_A2); + int paramType = PL_A3; + void *value = PL_A4; + + ros::NodeHandle n; + ros::ServiceClient client = n.serviceClient("RoboSherlock/overwrite_param"); + robosherlock_msgs::OverwriteParam srv; + + srv.request.annotatorName = *annotatorName; + srv.request.parameterName = *paramName; + srv.request.parameterType = paramType; + + switch(paramType) { + case robosherlock_msgs::OverwriteParam::Request::INT: + srv.request.parameterInteger = PL_A4; + break; + case robosherlock_msgs::OverwriteParam::Request::INT_VECTOR: + srv.request.parameterIntegerVector = getIntVector(PL_A4); + break; + case robosherlock_msgs::OverwriteParam::Request::BOOL: + srv.request.parameterBool = *(bool *)value; + break; + case robosherlock_msgs::OverwriteParam::Request::FLOAT: + srv.request.parameterFloat = PL_A4; + break; + case robosherlock_msgs::OverwriteParam::Request::FLOAT_VECTOR: + srv.request.parameterFloatVector = getFloatVector(PL_A4); + break; + case robosherlock_msgs::OverwriteParam::Request::STRING: + srv.request.parameterString = *(std::string *)value; + break; + case robosherlock_msgs::OverwriteParam::Request::STRING_VECTOR: + srv.request.parameterStringVector = getStringVector(PL_A4); + break; + + default: + std::cout << "Invalid parameter data type, aborting." << std::endl; + return FALSE; + } + + if(client.call(srv)) { + std::cout << "Calling RoboSherlock/overwrite_param was successful" << std::endl; + return TRUE; + } + else { + std::cout << "Calling RoboSherlock/overwrite_param was unsuccessful" << std::endl; + return FALSE; + } +} \ No newline at end of file From faf222a0c68bb362d15b7f7237a2dd167960e448 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Wed, 29 Apr 2020 00:25:43 +0200 Subject: [PATCH 10/13] Bugfix in reconfigure service, added reconfiguration to rdf_meta to fix name resolving. --- robosherlock/prolog/rs_query_reasoning.pl | 103 ++++++++++-------- .../src/flowcontrol/src/RSProcessManager.cpp | 2 +- 2 files changed, 58 insertions(+), 47 deletions(-) diff --git a/robosherlock/prolog/rs_query_reasoning.pl b/robosherlock/prolog/rs_query_reasoning.pl index 4eb31790..18f98863 100644 --- a/robosherlock/prolog/rs_query_reasoning.pl +++ b/robosherlock/prolog/rs_query_reasoning.pl @@ -59,7 +59,18 @@ set_annotator_output_type_domain(r,t,r), set_annotator_input_type_constraint(r,t,r), compute_annotator_output_type_domain(r,r,t), - compute_annotator_input_type_restriction(r,r,t). + compute_annotator_input_type_restriction(r,r,t), + % reconfiguration: + set_annotator_setup_names(r,t), + set_annotator_setup_output_type_domain(r,t,t,t), + set_annotator_setup_input_type_constraint(r,t,t,t), + set_annotator_setup_parameter(r,t,t,t), + load_annotator_setup(r,t), + load_annotator_setup_input(r,t), + load_annotator_setup_output(r,t), + load_annotator_setup_parameter(r,t,t,t), + find_annotator_setup_for_output_type_domain(r,t,t,t), + find_annotator_setup_for_input_type_constraint(r,t,t,t). @@ -70,13 +81,13 @@ compute_annotators(A) :- - owl_subclass_of(A,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#AnnotationComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#DetectionComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#IoComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#PeopleComponent'), - not(A = 'http://knowrob.org/kb/rs_components.owl#SegmentationComponent'). + owl_subclass_of(A,rs_components:'RoboSherlockComponent'), + not(A = rs_components:'RoboSherlockComponent'), + not(A = rs_components:'AnnotationComponent'), + not(A = rs_components:'DetectionComponent'), + not(A = rs_components:'IoComponent'), + not(A = rs_components:'PeopleComponent'), + not(A = rs_components:'SegmentationComponent'). % cache the annotators @@ -85,28 +96,28 @@ % assert domain restriction for an individual generated from a RoboSherlockComponents set_annotator_domain(AnnotatorI, Domain):- - owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), - owl_restriction_assert(restriction('http://knowrob.org/kb/rs_components.owl#outputDomain',all_values_from(union_of(Domain))),R), + owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), + owl_restriction_assert(restriction(rs_components:'outputDomain',all_values_from(union_of(Domain))),R), rdf_assert(AnnotatorI,rdf:type,R). %%%% set a domain constraint on the type of the annotator e.g. Primitive Shape annotator returns Shape annotations with value one of [a,b,c] %%%% set_annotator_output_type_domain(AnnotatorI, Domain, Type):- - owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_outputs(Annotator, Type),%% you can only set this restriction if the Type is defined as an output type owl_restriction_assert(restriction(Type,all_values_from(union_of(Domain))),R), rdf_assert(AnnotatorI,rdf:type,R). set_annotator_input_type_constraint(AnnotatorI, Constraint, Type):- - owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_inputs(Annotator, Type),%% you can only set this restriction if the Type is defined as an output type owl_restriction_assert(restriction(Type,all_values_from(union_of(Constraint))),R), rdf_assert(AnnotatorI,rdf:type,R). compute_annotator_output_type_domain(AnnotatorI, Type, Domain):- - owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_outputs(Annotator, Type), owl_has(AnnotatorI,rdf:type,R), @@ -114,7 +125,7 @@ rdf_has(R,owl:allValuesFrom,V),owl_description(V,union_of(Domain)). compute_annotator_input_type_restriction(AnnotatorI, Type, Domain):- - owl_individual_of(AnnotatorI,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + owl_individual_of(AnnotatorI,rs_components:'RoboSherlockComponent'), owl_individual_of(AnnotatorI,Annotator),!, compute_annotator_inputs(Annotator, Type), owl_has(AnnotatorI,rdf:type,R), @@ -126,13 +137,13 @@ compute_annotator_outputs(Annotator,Output) :- annotators(Annotator), owl_has(Annotator,rdfs:subClassOf, O), - owl_restriction(O, restriction('http://knowrob.org/kb/rs_components.owl#perceptualOutput',some_values_from(Output))). + owl_restriction(O, restriction(rs_components:'perceptualOutput',some_values_from(Output))). % Get inputs of Annotator compute_annotator_inputs(Annotator,Input) :- annotators(Annotator), owl_has(Annotator,rdfs:subClassOf,O), - owl_restriction(O, restriction('http://knowrob.org/kb/rs_components.owl#perceptualInputRequired',some_values_from(Input))). + owl_restriction(O, restriction(rs_components:'perceptualInputRequired',some_values_from(Input))). % cache outputs/inputs :- forall(compute_annotator_outputs(A,O), assert(annotator_outputs(A,O)) ). @@ -357,24 +368,24 @@ build_pipeline(Annotators, Pipeline). assert_test_pipeline:- - kb_create('http://knowrob.org/kb/rs_components.owl#CollectionReader',_),kb_create('http://knowrob.org/kb/rs_components.owl#ImagePreprocessor',_), - kb_create('http://knowrob.org/kb/rs_components.owl#RegionFilter',_), - kb_create('http://knowrob.org/kb/rs_components.owl#NormalEstimator',_), - kb_create('http://knowrob.org/kb/rs_components.owl#PlaneAnnotator',_), - kb_create('http://knowrob.org/kb/rs_components.owl#ImageSegmentationAnnotator',_), - kb_create('http://knowrob.org/kb/rs_components.owl#PointCloudClusterExtractor',_), - kb_create('http://knowrob.org/kb/rs_components.owl#ClusterMerger',_), - kb_create('http://knowrob.org/kb/rs_components.owl#Cluster3DGeometryAnnotator',GI),set_annotator_output_type_domain(GI,['http://knowrob.org/kb/rs_components.owl#Small','http://knowrob.org/kb/rs_components.owl#Big','http://knowrob.org/kb/rs_components.owl#Medium'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationGeometry'), - kb_create('http://knowrob.org/kb/rs_components.owl#PrimitiveShapeAnnotator',PI),set_annotator_output_type_domain(PI,['http://knowrob.org/kb/rs_components.owl#Box','http://knowrob.org/kb/rs_components.owl#Round'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape'), - kb_create('http://knowrob.org/kb/rs_components.owl#ClusterColorHistogramCalculator',CI),set_annotator_output_type_domain(CI,['http://knowrob.org/kb/rs_components.owl#Yellow','http://knowrob.org/kb/rs_components.owl#Blue'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationSemanticcolor'), - kb_create('http://knowrob.org/kb/rs_components.owl#SacModelAnnotator',SI),set_annotator_output_type_domain(SI,['http://knowrob.org/kb/rs_components.owl#Cylinder'],'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape'), - kb_create('http://knowrob.org/kb/rs_components.owl#PCLDescriptorExtractor',_), - kb_create('http://knowrob.org/kb/rs_components.owl#CaffeAnnotator',_), - kb_create('http://knowrob.org/kb/rs_components.owl#KnnAnnotator',KNNI),set_annotator_output_type_domain(KNNI,[kitchen:'WhiteCeramicIkeaBowl', kitchen:'KoellnMuesliKnusperHonigNuss'], 'http://knowrob.org/kb/rs_components.owl#RsAnnotationClassification'), - kb_create('http://knowrob.org/kb/rs_components.owl#HandleAnnotator',HI),set_annotator_output_type_domain(HI,['http://knowrob.org/kb/rs_components.owl#Handle'], 'http://knowrob.org/kb/rs_components.owl#RsAnnotationDetection'). + kb_create(rs_components:'CollectionReader',_),kb_create(rs_components:'ImagePreprocessor',_), + kb_create(rs_components:'RegionFilter',_), + kb_create(rs_components:'NormalEstimator',_), + kb_create(rs_components:'PlaneAnnotator',_), + kb_create(rs_components:'ImageSegmentationAnnotator',_), + kb_create(rs_components:'PointCloudClusterExtractor',_), + kb_create(rs_components:'ClusterMerger',_), + kb_create(rs_components:'Cluster3DGeometryAnnotator',GI),set_annotator_output_type_domain(GI,[rs_components:'Small',rs_components:'Big',rs_components:'Medium'],rs_components:'RsAnnotationGeometry'), + kb_create(rs_components:'PrimitiveShapeAnnotator',PI),set_annotator_output_type_domain(PI,[rs_components:'Box',rs_components:'Round'],rs_components:'RsAnnotationShape'), + kb_create(rs_components:'ClusterColorHistogramCalculator',CI),set_annotator_output_type_domain(CI,[rs_components:'Yellow',rs_components:'Blue'],rs_components:'RsAnnotationSemanticcolor'), + kb_create(rs_components:'SacModelAnnotator',SI),set_annotator_output_type_domain(SI,[rs_components:'Cylinder'],rs_components:'RsAnnotationShape'), + kb_create(rs_components:'PCLDescriptorExtractor',_), + kb_create(rs_components:'CaffeAnnotator',_), + kb_create(rs_components:'KnnAnnotator',KNNI),set_annotator_output_type_domain(KNNI,[kitchen:'WhiteCeramicIkeaBowl', kitchen:'KoellnMuesliKnusperHonigNuss'], rs_components:'RsAnnotationClassification'), + kb_create(rs_components:'HandleAnnotator',HI),set_annotator_output_type_domain(HI,[rs_components:'Handle'], rs_components:'RsAnnotationDetection'). assert_query:- - assert(requestedValueForKey(shape,'http://knowrob.org/kb/rs_components.owl#Box')). + assert(requestedValueForKey(shape,rs_components:'Box')). assert_query_lang:- assert(rs_query_predicate(shape)), @@ -391,12 +402,12 @@ assert(rs_query_predicate(timestamp)), assert(rs_query_predicate(location)), assert(rs_query_predicate(has-ingredient)), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationShape',A),assert(rs_type_for_predicate(shape, A)), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationSemanticcolor',B),assert(rs_type_for_predicate(color, B)), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationGeometry',C), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationDetection',D), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationClassification',E), - rdf_global_id('http://knowrob.org/kb/rs_components.owl#RsAnnotationPose',F), + rdf_global_id(rs_components:'RsAnnotationShape',A),assert(rs_type_for_predicate(shape, A)), + rdf_global_id(rs_components:'RsAnnotationSemanticcolor',B),assert(rs_type_for_predicate(color, B)), + rdf_global_id(rs_components:'RsAnnotationGeometry',C), + rdf_global_id(rs_components:'RsAnnotationDetection',D), + rdf_global_id(rs_components:'RsAnnotationClassification',E), + rdf_global_id(rs_components:'RsAnnotationPose',F), assert(rs_type_for_predicate(size, C)), assert(rs_type_for_predicate(detection, D)), assert(rs_type_for_predicate(class, E)), @@ -419,7 +430,7 @@ retractall(rs_type_for_predicate(_,_)). retract_all_annotators:- - forall(owl_subclass_of(S,'http://knowrob.org/kb/rs_components.owl#RoboSherlockComponent'), + forall(owl_subclass_of(S,rs_components:'RoboSherlockComponent'), rdf_retractall(_,rdf:type,S)). retract_query_assertions:- @@ -429,11 +440,11 @@ assert_reconfiguration_pipeline:- assert_test_pipeline, - owl_individual_of(I, 'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + owl_individual_of(I, rs_components:'SacModelAnnotator'), set_annotator_setup_names(I, ['SetupCylinder', 'SetupSphere']), - set_annotator_setup_output_type_domain(I, 'SetupCylinder', 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Cylinder']), - set_annotator_setup_output_type_domain(I, 'SetupSphere', 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Sphere']), - set_annotator_setup_input_type_constraint(I, 'SetupSphere', 'http://knowrob.org/kb/rs_components.owl#perceptualInputRequired', ['http://knowrob.org/kb/rs_components.owl#RsSceneMergedhypothesis'] ). + set_annotator_setup_output_type_domain(I, 'SetupCylinder', rs_components:'RsAnnotationShape', [rs_components:'Cylinder']), + set_annotator_setup_output_type_domain(I, 'SetupSphere', rs_components:'RsAnnotationShape', [rs_components:'Sphere']), + set_annotator_setup_input_type_constraint(I, 'SetupSphere', rs_components:'perceptualInputRequired', [rs_components:'RsSceneMergedhypothesis'] ). set_annotator_setup_names(AnnotatorI, Setups) :- @@ -495,12 +506,12 @@ %% TEST TODO: REMOVE find_sphere_setup(A, S) :- - find_annotator_setup_for_output_type_domain(A, S, 'http://knowrob.org/kb/rs_components.owl#RsAnnotationShape', ['http://knowrob.org/kb/rs_components.owl#Sphere']). + find_annotator_setup_for_output_type_domain(A, S, rs_components:'RsAnnotationShape', [rs_components:'Sphere']). load_sphere_setup:- - owl_individual_of(I,'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + owl_individual_of(I,rs_components:'SacModelAnnotator'), load_annotator_setup_output(I, 'SetupSphere'). load_cylinder_setup:- - owl_individual_of(I,'http://knowrob.org/kb/rs_components.owl#SacModelAnnotator'), + owl_individual_of(I,rs_components:'SacModelAnnotator'), load_annotator_setup(I, 'SetupCylinder'). \ No newline at end of file diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 87c76613..6590721f 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -590,7 +590,7 @@ bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::Reconfigure if(result != aCaps.end()) { aCap = result->second; // TODO: Update input- and output-capabilities here - res.result = true; + res.result = engine_->reconfigureAnnotator(req.annotatorName); } else { outError("Annotator " << req.annotatorName << " could not be found."); From a7fac2f53f8f9ef0e1ba6b9eb2c0cf3f5f595207 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Tue, 19 May 2020 22:20:02 +0200 Subject: [PATCH 11/13] It works now --- robosherlock/config/config_reconfig_demo.ini | 12 ++ .../analysis_engines/reconfig_demo.yaml | 2 +- .../annotators/annotation/CaffeAnnotator.yaml | 19 +++ .../annotation/SacModelAnnotator.yaml | 13 +-- robosherlock/prolog/rs_query_reasoning.pl | 26 +++-- .../core/include/robosherlock/utils/common.h | 30 ++++- .../flowcontrol/RSAggregateAnalysisEngine.h | 41 +++++++ .../src/RSAggregateAnalysisEngine.cpp | 9 +- .../src/flowcontrol/src/RSProcessManager.cpp | 87 +++++++------- .../flowcontrol/src/YamlToXMLConverter.cpp | 66 ++++++++--- .../queryanswering/KnowledgeEngine.h | 9 +- .../queryanswering/src/PrologCPPQueries.cpp | 109 ++++-------------- robosherlock_msgs/srv/OverwriteParam.srv | 21 +--- 13 files changed, 251 insertions(+), 193 deletions(-) create mode 100644 robosherlock/config/config_reconfig_demo.ini diff --git a/robosherlock/config/config_reconfig_demo.ini b/robosherlock/config/config_reconfig_demo.ini new file mode 100644 index 00000000..26cbaa78 --- /dev/null +++ b/robosherlock/config/config_reconfig_demo.ini @@ -0,0 +1,12 @@ +[camera] +interface=MongoDB + +[mongodb] +host=localhost +db=classification_test_training +continual=false +loop=true +playbackSpeed=0.0 + +[tf] +semanticMap=semantic_map_iai_kitchen.yaml diff --git a/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml index f5edd174..7010b65c 100644 --- a/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml +++ b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml @@ -11,4 +11,4 @@ fixedflow: - ClusterMerger - SacModelAnnotator CollectionReader: - camera_config_files: ['config_kinect_robot.ini'] + camera_config_files: ['config_reconfig_demo.ini'] diff --git a/robosherlock/descriptors/annotators/annotation/CaffeAnnotator.yaml b/robosherlock/descriptors/annotators/annotation/CaffeAnnotator.yaml index 5bf1a432..96459561 100644 --- a/robosherlock/descriptors/annotators/annotation/CaffeAnnotator.yaml +++ b/robosherlock/descriptors/annotators/annotation/CaffeAnnotator.yaml @@ -11,3 +11,22 @@ parameters: capabilities: inputs: ['rs.scene.MergedHypothesis'] outputs: ['rs.annotation.Features'] + +reconfiguration: + # BVLC setup + setup_bvlc: + parameters: + caffe_annotator_model_file: '/caffe/models/bvlc_reference_caffenet/deploy.prototxt' # paths are relative to rs_resources + caffe_annotator_trained_file: '/caffe/models/bvlc_reference_caffenet/bvlc_reference_caffenet.caffemodel' + caffe_annotator_mean_file: '/caffe/data/imagenet_mean.binaryproto' + caffe_annotator_label_file: '/caffe/data/synset_words.txt' + caffe_annotator_noramlize: true + + # VHF setup + setup_vfh: + parameters: + caffe_annotator_model_file: 'vfh path' # paths are relative to rs_resources + caffe_annotator_trained_file: 'vfh path' + caffe_annotator_mean_file: 'vfh path' + caffe_annotator_label_file: 'vfh path' + caffe_annotator_noramlize: true \ No newline at end of file diff --git a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml index dac378ee..9df9f19d 100644 --- a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml +++ b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml @@ -21,7 +21,7 @@ parameters: minPoints: 200 radiusLimit1: 0.01 radiusLimit2: 0.5 - sacModel: Cylinder + sacModel: "CYLINDER" useNormals: true reconfiguration: @@ -34,15 +34,14 @@ reconfiguration: # Overwrite or define new parameters: parameters: - test_param: "success" - sacModel: Sphere + sacModel: "SPHERE" # Example setup - setup_example: + setup_cylinder: capabilities: outputs: - - rs.annotation.Shape: [example] - domain: [example] + - rs.annotation.Shape: [cylinder] + domain: [cylinder] parameters: - useNormals: false \ No newline at end of file + sacModel: "CYLINDER" \ No newline at end of file diff --git a/robosherlock/prolog/rs_query_reasoning.pl b/robosherlock/prolog/rs_query_reasoning.pl index 18f98863..d503ae4b 100644 --- a/robosherlock/prolog/rs_query_reasoning.pl +++ b/robosherlock/prolog/rs_query_reasoning.pl @@ -43,9 +43,11 @@ assert_test_case/0, retract_all_annotators/0, retract_query_assertions/0, - set_annotator_setup_names/2, - assert_reconfiguration_pipeline/0 + assert_reconfiguration_pipeline/0, + load_sphere_setup/0, + find_sphere_setup/2, + test_overwrite_param/0 ]). :- rdf_meta @@ -73,6 +75,8 @@ find_annotator_setup_for_input_type_constraint(r,t,t,t). +:- use_foreign_library('librs_prologQueries.so'). + %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% % Pipeline Planning @@ -470,8 +474,9 @@ annotator_setup_names(AnnotatorI, Setup), %% check if setup exists %% Update output and input load_annotator_setup_input(AnnotatorI, Setup), - load_annotator_setup_output(AnnotatorI, Setup). - %% TODO: Call Cpp Rule to reconfigure annotator + load_annotator_setup_output(AnnotatorI, Setup), + write('Loading new setup: '), nl, write(AnnotatorI), nl, write(Setup), + cpp_reconfigure_annotator(AnnotatorI, Setup). load_annotator_setup_input(AnnotatorI, Setup) :- annotator_setup_input_type((AnnotatorI, Setup), Type), @@ -491,8 +496,9 @@ load_annotator_setup_parameter(AnnotatorI, Setup, Parameter, Value) :- annotator_setup_names(AnnotatorI, Setup), %% check if setup exists - annotator_setup_parameter((AnnotatorI, Setup), Parameter, Value). - %% TODO: Overwrite param with Cpp Rule + annotator_setup_parameter((AnnotatorI, Setup), Parameter, Value), + write('Overwriting param now'), nl, write(AnnotatorI), nl, + cpp_overwrite_param(AnnotatorI, Parameter, 2, Value). find_annotator_setup_for_output_type_domain(AnnotatorI, Setup, Type, Domain) :- @@ -509,9 +515,11 @@ find_annotator_setup_for_output_type_domain(A, S, rs_components:'RsAnnotationShape', [rs_components:'Sphere']). load_sphere_setup:- - owl_individual_of(I,rs_components:'SacModelAnnotator'), - load_annotator_setup_output(I, 'SetupSphere'). + cpp_reconfigure_annotator('SacModelAnnotator', 'setup_spheres'). load_cylinder_setup:- owl_individual_of(I,rs_components:'SacModelAnnotator'), - load_annotator_setup(I, 'SetupCylinder'). \ No newline at end of file + load_annotator_setup(I, 'SetupCylinder'). + +test_overwrite_param:- + cpp_overwrite_param('SacModelAnnotator', 'sacModel', ['CYLINDER']). \ No newline at end of file diff --git a/robosherlock/src/core/include/robosherlock/utils/common.h b/robosherlock/src/core/include/robosherlock/utils/common.h index f3589f58..8af42b27 100644 --- a/robosherlock/src/core/include/robosherlock/utils/common.h +++ b/robosherlock/src/core/include/robosherlock/utils/common.h @@ -37,12 +37,33 @@ #include + namespace rs { #define AE_SEARCHPATH "/descriptors/analysis_engines/" #define ANNOT_SEARCHPATH "/descriptors/annotators/" +struct AnnotatorSetup +{ + /** + * @brief Holds the type name for each parameter: + */ + std::map paramTypes; + /** + * @brief Holds the value for each parameter in this setup: + */ + std::map> paramValues; + /** + * @brief rOutputTypeValueDomains mapping of output domain values after reconfiguring + */ + std::map> rOutputTypeValueDomains; + /** + * @brief rInputTypeValueRestrictions mapping of input restrictions after reconfiguring + */ + std::map> rInputTypeValueRestrictions; +}; + struct AnnotatorCapabilities { /** @@ -58,16 +79,15 @@ struct AnnotatorCapabilities */ std::map> iTypeValueRestrictions; /** - * @brief rOutputTypeValueDomains mapping of output domain values after reconfiguring + * @brief The default setup */ - std::map> rOutputTypeValueDomains; + AnnotatorSetup defaultSetup; /** - * @brief rInputTypeValueRestrictions mapping of input restrictions after reconfiguring + * @brief Contains all setups for this annotator */ - std::map> rInputTypeValueRestrictions; + std::map reconfigurationSetups; }; - namespace common { diff --git a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h index c059eafa..88a5ac8b 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/RSAggregateAnalysisEngine.h @@ -311,6 +311,12 @@ class RSAggregateAnalysisEngine : public uima::internal::AggregateEngine cr_context->assignValue(UnicodeString(param_name.c_str()), (UnicodeString) param.c_str()); } + /** + * @brief overwriteParam specific case for vectors of strings because of uima working with UnicodeStrings + * @param ae_ame + * @param param_name + * @param param + */ void overwriteParam(const std::string &ae_name, const std::string ¶m_name, const std::vector ¶m) { uima::AnnotatorContext &annotContext = getAnnotatorContext(); @@ -325,6 +331,41 @@ class RSAggregateAnalysisEngine : public uima::internal::AggregateEngine cr_context->assignValue(UnicodeString(param_name.c_str()), conversionString); } + /** + * @brief overwriteParam specific case for strings because of uima working with UnicodeStrings + * @param ae_ame Name of the Annotator + * @param param_name Name of the parameter + * @param param_value New value + * @param param_type Name of the type as string + */ + void overwriteParam(const std::string &ae_name, const std::string ¶m_name, const std::vector ¶m_value, const std::string ¶m_type){ + if(param_type == "String") + overwriteParam(ae_name, param_name, param_value[0]); + else if(param_type == "Integer") + overwriteParam(ae_name, param_name, std::stoi(param_value[0])); + else if(param_type == "Float") + overwriteParam(ae_name, param_name, std::stod(param_value[0])); + else if(param_type == "Boolean") + overwriteParam(ae_name, param_name, param_value[0] == "True"); + else if(param_type == "ListString") + overwriteParam(ae_name, param_name, param_value); + else if(param_type == "ListInteger") { + std::vector temp; + for(string s : param_value) + temp.push_back(std::stoi(s)); + + overwriteParam(ae_name, param_name, temp); + } + else if(param_type == "ListFloat") { + std::vector temp; + for(string s : param_value) + temp.push_back(std::stod(s)); + + overwriteParam(ae_name, param_name, temp); + } + // ListBoolean not supported. + } + /** * @brief Reconfigures a single annotator * @param annotatorIdx Index of annotator in pipeline diff --git a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp index efd8beb8..ac3fe86e 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -406,12 +406,9 @@ std::string convertAnnotatorYamlToXML(std::string annotator_name, if (delegate_capabilities[annotator_name].iTypeValueRestrictions.empty()) delegate_capabilities[annotator_name].iTypeValueRestrictions = converter.getAnnotatorCapabilities().iTypeValueRestrictions; - if (delegate_capabilities[annotator_name].rOutputTypeValueDomains.empty()) - delegate_capabilities[annotator_name].rOutputTypeValueDomains = - converter.getAnnotatorCapabilities().rOutputTypeValueDomains; - if(delegate_capabilities[annotator_name].rInputTypeValueRestrictions.empty()) - delegate_capabilities[annotator_name].rInputTypeValueRestrictions = - converter.getAnnotatorCapabilities().rInputTypeValueRestrictions; + + delegate_capabilities[annotator_name].defaultSetup = converter.getAnnotatorCapabilities().defaultSetup; + delegate_capabilities[annotator_name].reconfigurationSetups = converter.getAnnotatorCapabilities().reconfigurationSetups; } } catch (YAML::ParserException e) diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index 6590721f..d35c4bcb 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -577,9 +577,15 @@ bool RSProcessManager::highlightResultsInCloud(const std::vector &filter, bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, robosherlock_msgs::ReconfigureAnnotator::Response &res) { + if(req.annotatorName.empty()) { + outError("No annotator name set. Aborting.."); + res.result = false; + return false; + } + if(req.setupName.empty()) { // No setup provided; reconfigure only. - outInfo("No setup name provided, just calling reconfigure() now."); + outInfo("No setup name provided, just calling reconfigure() on \"" << req.annotatorName << "\"."); res.result = engine_->reconfigureAnnotator(req.annotatorName); } else { @@ -589,8 +595,30 @@ bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::Reconfigure if(result != aCaps.end()) { aCap = result->second; - // TODO: Update input- and output-capabilities here - res.result = engine_->reconfigureAnnotator(req.annotatorName); + auto setup = aCap.reconfigurationSetups.find(req.setupName); + + // Check if requested setup exists: + if(setup != aCap.reconfigurationSetups.end()) { + // Load all parameters from setup: + map::iterator paramIt; + for( paramIt = aCap.reconfigurationSetups[req.setupName].paramTypes.begin(); + paramIt != aCap.reconfigurationSetups[req.setupName].paramTypes.end(); + paramIt++) + { + std::string parameter = paramIt->first; + std::string type = paramIt->second; + std::vector values = aCap.reconfigurationSetups[req.setupName].paramValues[paramIt->first]; + + outInfo("Updating parameter \"" << parameter << "\" of type " << type << " with the new value \"" << values[0] << "\"."); + engine_->overwriteParam(req.annotatorName, parameter, values, type); + } + + outInfo("Loading setup \"" << req.setupName << "\" for the annotator \"" << req.annotatorName << "\"."); + res.result = engine_->reconfigureAnnotator(req.annotatorName); + } + else { + outError("The requested setup \"" << req.setupName << "\" for the annotator \"" << req.annotatorName << "\" could not be found."); + } } else { outError("Annotator " << req.annotatorName << " could not be found."); @@ -602,44 +630,25 @@ bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::Reconfigure bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, robosherlock_msgs::OverwriteParam::Response &res) { - switch(req.parameterType) { - case robosherlock_msgs::OverwriteParamRequest::INT: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterInteger); - break; - case robosherlock_msgs::OverwriteParamRequest::INT_VECTOR: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterIntegerVector); - break; - case robosherlock_msgs::OverwriteParamRequest::BOOL: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBool); - break; - case robosherlock_msgs::OverwriteParamRequest::BOOL_VECTOR: - //engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterBoolVector); - // REASON: No valid template-function found during compile-time - outError("Vectors of booleans are currently not supported by the OverwriteParamService."); - res.result = false; - return false; - case robosherlock_msgs::OverwriteParamRequest::FLOAT: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterFloat); - break; - case robosherlock_msgs::OverwriteParamRequest::FLOAT_VECTOR: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterFloatVector); - break; - case robosherlock_msgs::OverwriteParamRequest::STRING: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterString); - break; - case robosherlock_msgs::OverwriteParamRequest::STRING_VECTOR: - engine_->overwriteParam(req.annotatorName, req.parameterName, req.parameterStringVector); - break; - - default: - outError("Invalid data type in OverwriteParam Service Request."); + auto aCaps = engine_->getDelegateAnnotatorCapabilities(); + auto result = aCaps.find(req.annotatorName); + rs::AnnotatorCapabilities aCap; + + if(result != aCaps.end()) { + aCap = result->second; + + if(aCap.defaultSetup.paramTypes.count(req.parameterName) == 1) { + engine_->overwriteParam(req.annotatorName, req.parameterName, req.values, aCap.defaultSetup.paramTypes[req.parameterName]); + outInfo("OverwriteParam finished successfully."); + res.result = true; + } + else { + outError("OverwriteParam failed!"); res.result = false; - return false; - } + } - outInfo("OverwriteParam finished successfully."); - res.result = true; - return true; + return res.result; + } } template bool RSProcessManager::drawResultsOnImage(const std::vector &filter, diff --git a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp index 5af634dd..f3785640 100644 --- a/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp +++ b/robosherlock/src/flowcontrol/src/YamlToXMLConverter.cpp @@ -466,6 +466,9 @@ bool YamlToXMLConverter::generateAnnotatorConfigParamInfo(const YAML::Node &node configParamSettings.append("\n"); configParamSettings.append("\n"); + // Save parameter info into default setup: + annotCap.defaultSetup.paramTypes[configName] = type; + annotCap.defaultSetup.paramValues[configName] = { mit->second.as() }; } else if(mit->second.Type() == YAML::NodeType::Sequence) // list { @@ -524,6 +527,8 @@ bool YamlToXMLConverter::generateAnnotatorConfigParamInfo(const YAML::Node &node configParamSettings.append("\n"); configParamSettings.append("\n"); + annotCap.defaultSetup.paramTypes[configName] = type; + annotCap.defaultSetup.paramValues[configName] = listValue; } else { @@ -643,9 +648,7 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno } else { - ostringstream id; - id << setup_name << ":" << val; - annotCap.rInputTypeValueRestrictions[id.str()] = std::vector(); + annotCap.reconfigurationSetups[setup_name].rInputTypeValueRestrictions[val] = std::vector(); } } if(sit->Type() == YAML::NodeType::Map) @@ -664,9 +667,7 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno } else { - ostringstream id; - id << setup_name << ":" << val; - annotCap.rInputTypeValueRestrictions[id.str()] = e.second.as>(); + annotCap.reconfigurationSetups[setup_name].rInputTypeValueRestrictions[val] = e.second.as>(); } } } @@ -700,9 +701,7 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno } else { - ostringstream id; - id << setup_name << ":" << val; - annotCap.rOutputTypeValueDomains[id.str()] = std::vector(); + annotCap.reconfigurationSetups[setup_name].rOutputTypeValueDomains[val] = std::vector(); } } if(n.Type() == YAML::NodeType::Map) @@ -720,9 +719,7 @@ bool YamlToXMLConverter::parseCapabInfo(const YAML::Node &node, std::string anno } else { - ostringstream id; - id << setup_name << ":" << val; - annotCap.rOutputTypeValueDomains[id.str()] = e.second.as>(); + annotCap.reconfigurationSetups[setup_name].rOutputTypeValueDomains[val] = e.second.as>(); } } } @@ -800,6 +797,12 @@ bool YamlToXMLConverter::parseReconfigurationInfo(const YAML::Node &node) { string setup_name = it->first.as(); + if(setup_name.empty()){ + continue; + } + + outInfo("Reconfiguration: Found setup " << setup_name); + for(YAML::const_iterator sit = it->second.begin(); sit != it->second.end(); ++sit) { if(sit->first.Type() == YAML::NodeType::Scalar) @@ -808,11 +811,48 @@ bool YamlToXMLConverter::parseReconfigurationInfo(const YAML::Node &node) if(node_name == CAPAB_NODE_NAME) { + outInfo("Reconfiguration: Found capabilities for setup " << setup_name); parseCapabInfo(sit->second, "", setup_name); } else if(node_name == CONFIG_PARAM_NODE_NAME) { - // TODO: Also save params for reconfiguration? + outInfo("Reconfiguration: Found parameter definition for " << setup_name); + + if(sit->second.Type() == YAML::NodeType::Map) + { + for(YAML::const_iterator mit = sit->second.begin(); mit != sit->second.end(); ++mit) + { + string configName = mit->first.as(); + outInfo("Reconfiguration: Saving parameter " << configName); + + if(mit->second.Type() == YAML::NodeType::Scalar) + { + // Single values: + outInfo("Saving " << setup_name << " - " << configName << " : " << getType(mit->second) << " value:" << mit->second.as()); + annotCap.reconfigurationSetups[setup_name].paramTypes[configName] = getType(mit->second); + annotCap.reconfigurationSetups[setup_name].paramValues[configName] = { mit->second.as() }; + } + else if(mit->second.Type() == YAML::NodeType::Sequence) + { + // Lists: + YAML::const_iterator listIt = mit->second.begin(); + string type = getType(*listIt); + vector listValue = mit->second.as>(); + + outInfo("Saving " << setup_name << " - " << configName << " : " << getType(mit->second) << " value:" << mit->second.as()); + annotCap.reconfigurationSetups[setup_name].paramTypes[configName] = "List" + getType(mit->second); + annotCap.reconfigurationSetups[setup_name].paramValues[configName] = listValue; + } + else { + // ERROR: Invalid type + outError("Reconfiguration: Invalid data type"); + } + } + } + else { + // ERROR: use map structure + outError("Reconfiguration: Please use map structure"); + } } else { diff --git a/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h index 5e9108d3..20a26563 100644 --- a/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h +++ b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h @@ -169,8 +169,9 @@ class KnowledgeEngine outDebug(individualOfAnnotator); std::map> inputRestrictions = annotatorData.second.iTypeValueRestrictions; std::map> outputDomains = annotatorData.second.oTypeValueDomains; - std::map> reconfigInputRestrictions = annotatorData.second.rInputTypeValueRestrictions; - std::map> reconfigOutputDomains = annotatorData.second.rOutputTypeValueDomains; + //std::map> reconfigInputRestrictions = annotatorData.second.rInputTypeValueRestrictions; + //std::map> reconfigOutputDomains = annotatorData.second.rOutputTypeValueDomains; + // TODO: Get info from RSAnnotatorSetup object if(!inputRestrictions.empty()) { @@ -242,7 +243,7 @@ class KnowledgeEngine } } - if(!reconfigInputRestrictions.empty()) { + /*if(!reconfigInputRestrictions.empty()) { // TODO: Add assertations regarding to input restriction reconfiguration } @@ -254,7 +255,7 @@ class KnowledgeEngine outInfo(e.first << " <==> " << e.second[0]); } outInfo(">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>"); - } + }*/ } } else diff --git a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp index cace2c86..90f9ea6b 100644 --- a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp +++ b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp @@ -204,121 +204,52 @@ PREDICATE(write_list, 1) } -/** - * Conversion methods, needed for overwrite_param service calls - */ - -std::vector getIntVector(PlTail prologList) -{ - std::vector result; - PlTerm e; - - while(prologList.next(e)) { - result.push_back(e); - } - - return result; -} - -// ROS FLOAT = DOUBLE! -std::vector getFloatVector(PlTail prologList) -{ - std::vector result; - PlTerm e; - - while(prologList.next(e)) { - result.push_back(*(double *)&e); - } - - return result; -} - -std::vector getStringVector(PlTail prologList) -{ - std::vector result; - PlTerm e; - - while(prologList.next(e)) { - result.push_back(static_cast((char *)e)); - } - return result; -} - - PREDICATE(cpp_reconfigure_annotator, 2) { - std::string *annotatorName, *setupName; - annotatorName = static_cast((void *) PL_A1); - setupName = static_cast((void *) PL_A2); + std::string annotatorName, setupName; + annotatorName = (std::string) PL_A1; + setupName = (std::string) PL_A2; ros::NodeHandle n; - ros::ServiceClient client = n.serviceClient("RoboSherlock/reconfigure_annotator"); + ros::ServiceClient client = n.serviceClient(std::string("RoboSherlock_") + getenv("USER") + "/reconfigure_annotator"); robosherlock_msgs::ReconfigureAnnotator srv; - srv.request.annotatorName = *annotatorName; - srv.request.setupName = *setupName; + srv.request.annotatorName = annotatorName; + srv.request.setupName = setupName; if(client.call(srv)) { - std::cout << "Calling RoboSherlock/reconfigure_annotator was successful" << std::endl; + std::cout << "Calling reconfigure_annotator was successful" << std::endl; return TRUE; } else { - std::cout << "Calling RoboSherlock/reconfigure_annotator was unsuccessful" << std::endl; + std::cerr << "Service call reconfigure_annotator failed!" << std::endl; return FALSE; } } -PREDICATE(cpp_overwrite_param, 4) +PREDICATE(cpp_overwrite_param, 3) { - std::string *annotatorName, *paramName; - annotatorName = static_cast((void *) PL_A1); - paramName = static_cast((void *) PL_A2); - int paramType = PL_A3; - void *value = PL_A4; + std::string annotatorName, paramName; + std::vector values; + annotatorName = (std::string) PL_A1; + paramName = (std::string) PL_A2; + values = (std::vector) PL_A3; ros::NodeHandle n; - ros::ServiceClient client = n.serviceClient("RoboSherlock/overwrite_param"); + ros::ServiceClient client = n.serviceClient(std::string("RoboSherlock_") + getenv("USER") + "/overwrite_param"); robosherlock_msgs::OverwriteParam srv; - srv.request.annotatorName = *annotatorName; - srv.request.parameterName = *paramName; - srv.request.parameterType = paramType; - - switch(paramType) { - case robosherlock_msgs::OverwriteParam::Request::INT: - srv.request.parameterInteger = PL_A4; - break; - case robosherlock_msgs::OverwriteParam::Request::INT_VECTOR: - srv.request.parameterIntegerVector = getIntVector(PL_A4); - break; - case robosherlock_msgs::OverwriteParam::Request::BOOL: - srv.request.parameterBool = *(bool *)value; - break; - case robosherlock_msgs::OverwriteParam::Request::FLOAT: - srv.request.parameterFloat = PL_A4; - break; - case robosherlock_msgs::OverwriteParam::Request::FLOAT_VECTOR: - srv.request.parameterFloatVector = getFloatVector(PL_A4); - break; - case robosherlock_msgs::OverwriteParam::Request::STRING: - srv.request.parameterString = *(std::string *)value; - break; - case robosherlock_msgs::OverwriteParam::Request::STRING_VECTOR: - srv.request.parameterStringVector = getStringVector(PL_A4); - break; - - default: - std::cout << "Invalid parameter data type, aborting." << std::endl; - return FALSE; - } + srv.request.annotatorName = annotatorName; + srv.request.parameterName = paramName; + srv.request.values = values; if(client.call(srv)) { - std::cout << "Calling RoboSherlock/overwrite_param was successful" << std::endl; + std::cout << "Calling overwrite_param was successful" << std::endl; return TRUE; } else { - std::cout << "Calling RoboSherlock/overwrite_param was unsuccessful" << std::endl; + std::cerr << "Service call overwrite_param failed!" << std::endl; return FALSE; } } \ No newline at end of file diff --git a/robosherlock_msgs/srv/OverwriteParam.srv b/robosherlock_msgs/srv/OverwriteParam.srv index 592f1a5d..32b9683f 100644 --- a/robosherlock_msgs/srv/OverwriteParam.srv +++ b/robosherlock_msgs/srv/OverwriteParam.srv @@ -1,26 +1,7 @@ string annotatorName string parameterName -uint8 parameterType +string[] values -int32 parameterInteger -float64 parameterFloat -string parameterString -bool parameterBool - -int32[] parameterIntegerVector -float64[] parameterFloatVector -string[] parameterStringVector -bool[] parameterBoolVector - -# Parameter Types: -uint8 INT = 0 -uint8 FLOAT = 1 -uint8 STRING = 2 -uint8 BOOL = 3 -uint8 INT_VECTOR = 4 -uint8 FLOAT_VECTOR = 5 -uint8 STRING_VECTOR = 6 -uint8 BOOL_VECTOR = 7 --- bool result From d2eb750acce82f5f3791dad45da9ccd2bfde6fa5 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Wed, 3 Jun 2020 18:18:47 +0200 Subject: [PATCH 12/13] Changes for debugging --- robosherlock/cmake/FindAPR.cmake | 30 ---- robosherlock/cmake/FindICUUC.cmake | 23 --- .../cmake/FindMongoClientLibrary.cmake | 31 ---- robosherlock/cmake/project_config.cmake.in | 6 - robosherlock/cmake/robosherlock.cmake | 152 ------------------ .../cmake/robosherlock_config.cmake.em | 17 -- robosherlock/config/config_reconfig_demo.ini | 2 +- .../analysis_engines/reconfig_demo.yaml | 14 +- .../annotation/SacModelAnnotator.yaml | 2 + robosherlock/prolog/rs_query_reasoning.pl | 12 +- .../src/RSAggregateAnalysisEngine.cpp | 3 + .../src/flowcontrol/src/RSProcessManager.cpp | 3 + robosherlock/src/flowcontrol/src/run.cpp | 2 +- robosherlock/src/flowcontrol/src/runAAE.cpp | 2 +- .../queryanswering/src/PrologCPPQueries.cpp | 6 +- .../include/uima/annotator_abase.hpp | 2 + 16 files changed, 40 insertions(+), 267 deletions(-) delete mode 100644 robosherlock/cmake/FindAPR.cmake delete mode 100644 robosherlock/cmake/FindICUUC.cmake delete mode 100644 robosherlock/cmake/FindMongoClientLibrary.cmake delete mode 100644 robosherlock/cmake/project_config.cmake.in delete mode 100644 robosherlock/cmake/robosherlock.cmake delete mode 100644 robosherlock/cmake/robosherlock_config.cmake.em diff --git a/robosherlock/cmake/FindAPR.cmake b/robosherlock/cmake/FindAPR.cmake deleted file mode 100644 index 30bf6233..00000000 --- a/robosherlock/cmake/FindAPR.cmake +++ /dev/null @@ -1,30 +0,0 @@ -# APR_LIBRARY_FOUND - system has Mongo Client -# APR_LIBRARY - Mongo Client Library -# APR_INCLUDE_DIR - Mongo Client Library - -find_package(PkgConfig) -pkg_check_modules(PC_LIBAPR QUIET apr-1) -set(LIBAPR_DEFINITIONS ${PC_LIBAPR_CFLAGS_OTHER}) - -find_path(LIBAPR_INCLUDE_DIR - apr.h - HINTS ${PC_LIBAPR_INCLUDEDIR} ${PC_LIBAPR_INCLUDE_DIRS} - DOC "Found LIBAPR include directory" -) - -find_library(LIBAPR_LIBRARY - NAMES apr-1.0 apr-1 libapr-1.0 libapr-1 - HINTS ${PC_LIBAPR_LIBDIR} ${PC_LIBAPR_LIBRARY_DIRS} - DOC "Found LIBAPR library" -) - -set(LIBAPR_LIBRARIES ${LIBAPR_LIBRARY} ) -set(LIBAPR_INCLUDE_DIRS ${LIBAPR_INCLUDE_DIR} ) - -include(FindPackageHandleStandardArgs) -# handle the QUIETLY and REQUIRED arguments and set LIBXML2_FOUND to TRUE -# if all listed variables are TRUE -find_package_handle_standard_args(LibAPR1 DEFAULT_MSG - LIBAPR_LIBRARY LIBAPR_INCLUDE_DIR) - -mark_as_advanced(LIBAPR_INCLUDE_DIR LIBAPR_LIBRARY ) diff --git a/robosherlock/cmake/FindICUUC.cmake b/robosherlock/cmake/FindICUUC.cmake deleted file mode 100644 index bc771646..00000000 --- a/robosherlock/cmake/FindICUUC.cmake +++ /dev/null @@ -1,23 +0,0 @@ -# ICUUC_LIBRARY_FOUND - system has ICUUC -# ICUUC_LIBRARY - ICUUC Library - -find_library(ICUUC_LIB - NAMES libicuuc.so - DOC "Found ICUUC library" - PATHS /usr/local/lib -) - -if(ICUUC_LIB) - set(ICUUC_LIBRARY ${ICUUC_LIB}) - set(ICUUC_LIBRARIES ${ICUUC_LIB}) - message(STATUS "Found ICUUC Library: ${ICUUC_LIB}") - set(ICUUC_LIBRARY_FOUND true) -else() - set(ICUUC_LIBRARY_FOUND false) - if(ICUUC_LIBRARY_FIND_REQUIRED) - message(FATAL_ERROR "ICUUC library not found!") - else() - message(STATUS "ICUUC library not found!") - endif() -endif() - diff --git a/robosherlock/cmake/FindMongoClientLibrary.cmake b/robosherlock/cmake/FindMongoClientLibrary.cmake deleted file mode 100644 index c1a57cbc..00000000 --- a/robosherlock/cmake/FindMongoClientLibrary.cmake +++ /dev/null @@ -1,31 +0,0 @@ -# MONGO_CLIENT_LIBRARY_FOUND - system has Mongo Client -# MONGO_CLIENT_LIBRARY - Mongo Client Library - -message(STATUS "Looking for Mongo Client Library...") - -find_library(MONGO_CLIENT_LIBRARY - NAMES libmongoclient.so - DOC "Found MONGO library" - PATHS /usr/local/lib -) - -if(MONGO_CLIENT_LIBRARY) - set(MONGO_CLIENT_LIBRARY_FOUND 1) - - if(NOT MONGO_CLIENT_LIBRARY_FIND_QUIETLY) - message(STATUS "Found Mongo CLient Library: ${MONGO_CLIENT_LIBRARY}") - endif(NOT MONGO_CLIENT_LIBRARY_FIND_QUIETLY) - -else(MONGO_CLIENT_LIBRARY) - - set(MONGO_CLIENT_LIBRARY_FOUND 0 CACHE BOOL "Mongo Client Library not found") - if(MONGO_CLIENT_LIBRARY_FIND_REQUIRED) - message(FATAL_ERROR "Mongo Client Library not found, error") - else() - MESSAGE(STATUS "Mongo Client Library not found, disabled") - endif() -endif(MONGO_CLIENT_LIBRARY) - -MARK_AS_ADVANCED(MONGO_CLIENT_LIBRARY) - - diff --git a/robosherlock/cmake/project_config.cmake.in b/robosherlock/cmake/project_config.cmake.in deleted file mode 100644 index 2e5b1896..00000000 --- a/robosherlock/cmake/project_config.cmake.in +++ /dev/null @@ -1,6 +0,0 @@ -set(${PROJECT_NAME}_NAMESPACE ${NAMESPACE}) -set(${PROJECT_NAME}_TYPESYSTEM_CPP_PATH ${TYPESYSTEM_CPP_PATH}) -set(${PROJECT_NAME}_TYPESYSTEM_XML_PATH ${TYPESYSTEM_XML_PATH}) -set(${PROJECT_NAME}_ANNOTATOR_PATH ${ANNOTATOR_PATH}) -set(${PROJECT_NAME}_ENGINE_PATH ${ENGINE_PATH}) - diff --git a/robosherlock/cmake/robosherlock.cmake b/robosherlock/cmake/robosherlock.cmake deleted file mode 100644 index e72a8103..00000000 --- a/robosherlock/cmake/robosherlock.cmake +++ /dev/null @@ -1,152 +0,0 @@ - -############################################################################# -## Check for c++11 support ## -############################################################################# -include(CheckCXXCompilerFlag) -check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) -if(COMPILER_SUPPORTS_CXX11) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") -else() - message(ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") -endif() - -############################################################################# -## Set cxx flags ## -############################################################################# -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DBT_USE_DOUBLE_PRECISION -Wno-deprecated") -# Unused warnings -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wuninitialized -Winit-self -Wunused-function -Wunused-label -Wunused-variable -Wunused-but-set-parameter")#-Wunused-but-set-variable -# Additional warnings -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wreorder -Warray-bounds -Wtype-limits -Wreturn-type -Wsequence-point -Wparentheses -Wmissing-braces -Wchar-subscripts -Wswitch -Wwrite-strings -Wenum-compare -Wempty-body")# -Wlogical-op") - -############################################################################# -## Check for openMP support ## -############################################################################# -find_package(OpenMP) -if(OPENMP_FOUND) - message(STATUS "OpenMP found.") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") -endif() - - -############################################################################# -## Check for Caffe Support ## -############################################################################# -find_package(Caffe QUIET) -if(Caffe_FOUND) - message(STATUS "Caffe FOUND! Building related components") - - include_directories(${Caffe_INCLUDE_DIRS}) - add_definitions( -DCAFFE_FOUND ${Caffe_DEFINITIONS}) - - set(RS_CAFFE_LIB rs_caffeProxy) - set(RS_WITH_CAFFE TRUE) -else() - set(RS_WITH_CAFFE FALSE) -endif(Caffe_FOUND) - - -############################################################################# -## Check for Protobuf Support ## -############################################################################# -find_package(Protobuf QUIET) -if(PROTOBUF_FOUND AND PROTOBUF_PROTOC_EXECUTABLE) - message (STATUS "Found Protobuf and Protobuf executable.") - set(RS_WEB_LIB rs_web) - set(RS_WITH_GG TRUE) -else() - set(RS_WITH_GG FALSE) -endif() - - -############################################################################# -## Adding include dirs defined in CPATH (needed for xstow) ## -############################################################################# -if($ENV{CPATH}) - string(REPLACE ":" ";" paths $ENV{CPATH}) - foreach(path ${paths}) - include_directories(${path}) - endforeach() -endif() - -############################################################################# -## Add library macro ## -############################################################################# -macro(rs_add_library libname) - add_library(${libname} SHARED ${ARGN}) - target_link_libraries(${libname} ${LIBAPR_LIBRARY} ${UIMA_LIBRARY} ${ICUUC_LIBRARY} ${catkin_LIBRARIES}) - set_target_properties(${libname} PROPERTIES PREFIX "") -endmacro(rs_add_library) - -############################################################################# -## Add executable macro ## -############################################################################# -macro(rs_add_executable execname) - add_executable(${execname} ${ARGN}) - target_link_libraries(${execname} ${LIBAPR_LIBRARY} ${UIMA_LIBRARY} ${ICUUC_LIBRARY} ${catkin_LIBRARIES}) -endmacro(rs_add_executable) - -############################################################################# -## Generate classes from the typesystem xml files ## -############################################################################# -macro(generate_type_system) - set(script ${RS_SCRIPT_PATH}/generate_typesystem.py) - set(projects ${PROJECT_NAME}:${NAMESPACE}:${TYPESYSTEM_XML_PATH}:${TYPESYSTEM_CPP_PATH}) - - foreach(arg ${ARGN}) - set(projects ${projects} ${arg}:${${arg}_NAMESPACE}:${${arg}_TYPESYSTEM_XML_PATH}:${${arg}_TYPESYSTEM_CPP_PATH}) - endforeach() - - execute_process(COMMAND python ${script} ${projects}) -endmacro(generate_type_system) - -############################################################################# -## Find all include directories for export ## -############################################################################# -macro(find_include_dirs result) - set(search_pattern -name "include" -type d) - - foreach(arg ${ARGN}) - set(exclude ${exclude} ! -path "${PROJECT_SOURCE_DIR}/${arg}/*") - endforeach() - - message(STATUS "find path: ${PROJECT_SOURCE_DIR}/${arg}") - - execute_process(COMMAND find "-L" ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern} OUTPUT_VARIABLE found_include_dirs) - message(STATUS "executed: find ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern}") - - message(STATUS "found include path: ${found_include_dirs}") - - if(NOT "${found_include_dirs}" STREQUAL "") - string(REPLACE "\n" "/\;" ${result} ${found_include_dirs}) - #message(STATUS "additional include dirs: ${${result}}") - endif() -endmacro(find_include_dirs) - -############################################################################# -## Hack for QT Creator to include all relevant files ## -############################################################################# -macro(find_additional_files) - set(search_pattern -type f) - - foreach(arg ${ARGN}) - set(exclude ${exclude} ! -path "${PROJECT_SOURCE_DIR}/${arg}/*") - endforeach() - execute_process(COMMAND find "-L" ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern} OUTPUT_VARIABLE found_files) - if(NOT "${found_files}" STREQUAL "") - string(REPLACE "\n" ";" found_files_list ${found_files}) - add_custom_target(${PROJECT_NAME}_additional_files SOURCES ${found_files_list}) - endif() -endmacro(find_additional_files) - -############################################################################# -## Message on option status ## -############################################################################# -macro(check_option var) - if(${var}) - message(STATUS "${var} activated") - else(${var}) - message(STATUS "${var} deactivated") - endif(${var}) -endmacro(check_option) - diff --git a/robosherlock/cmake/robosherlock_config.cmake.em b/robosherlock/cmake/robosherlock_config.cmake.em deleted file mode 100644 index 3827aa70..00000000 --- a/robosherlock/cmake/robosherlock_config.cmake.em +++ /dev/null @@ -1,17 +0,0 @@ -set(robosherlock_NAMESPACE rs) -@[if DEVELSPACE]@ - -set(robosherlock_TYPESYSTEM_CPP_PATH "@(PROJECT_SOURCE_DIR)/src/core/include/robosherlock/types") -set(robosherlock_TYPESYSTEM_XML_PATH "@(PROJECT_SOURCE_DIR)/descriptors/typesystem") -set(robosherlock_ANNOTATOR_PATH "@(PROJECT_SOURCE_DIR)/descriptors/annotators") -set(robosherlock_ENGINE_PATH "@(PROJECT_SOURCE_DIR)/descriptors/analysis_engines") -set(RS_SCRIPT_PATH "@(PROJECT_SOURCE_DIR)/scripts") -set(RS_PROJECT_CONFIG "@(PROJECT_SOURCE_DIR)/cmake/project_config.cmake.in") -@[else]@ -set(robosherlock_TYPESYSTEM_CPP_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_INCLUDE_DESTINATION)/types") -set(robosherlock_TYPESYSTEM_XML_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/typesystem") -set(robosherlock_ANNOTATOR_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/annotators") -set(robosherlock_ENGINE_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/analysis_engines") -set(RS_SCRIPT_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/scripts") -set(RS_PROJECT_CONFIG "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/cmake/project_config.cmake.in") -@[end if]@ diff --git a/robosherlock/config/config_reconfig_demo.ini b/robosherlock/config/config_reconfig_demo.ini index 26cbaa78..7c033644 100644 --- a/robosherlock/config/config_reconfig_demo.ini +++ b/robosherlock/config/config_reconfig_demo.ini @@ -3,7 +3,7 @@ interface=MongoDB [mongodb] host=localhost -db=classification_test_training +db=classification_test_table continual=false loop=true playbackSpeed=0.0 diff --git a/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml index 7010b65c..ef04a229 100644 --- a/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml +++ b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml @@ -6,9 +6,21 @@ fixedflow: - PointCloudFilter - NormalEstimator - PlaneAnnotator - - ImageSegmentationAnnotator - PointCloudClusterExtractor - ClusterMerger - SacModelAnnotator + - CaffeAnnotator + - KnnAnnotator + #- ReconfigAnnotator + CollectionReader: camera_config_files: ['config_reconfig_demo.ini'] + +PointCloudFilter: + minX: -1.0 + maxX: 1.0 + minY: 0.0 + maxY: 1.0 + minZ: 0.0 + maxZ: 1.0 + transform_cloud: true diff --git a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml index 9df9f19d..a8ae274f 100644 --- a/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml +++ b/robosherlock/descriptors/annotators/annotation/SacModelAnnotator.yaml @@ -34,6 +34,7 @@ reconfiguration: # Overwrite or define new parameters: parameters: + distanceThreshold: 0.10 sacModel: "SPHERE" # Example setup @@ -44,4 +45,5 @@ reconfiguration: domain: [cylinder] parameters: + minPoints: 400 sacModel: "CYLINDER" \ No newline at end of file diff --git a/robosherlock/prolog/rs_query_reasoning.pl b/robosherlock/prolog/rs_query_reasoning.pl index d503ae4b..daff8267 100644 --- a/robosherlock/prolog/rs_query_reasoning.pl +++ b/robosherlock/prolog/rs_query_reasoning.pl @@ -47,7 +47,9 @@ assert_reconfiguration_pipeline/0, load_sphere_setup/0, find_sphere_setup/2, - test_overwrite_param/0 + test_overwrite_param/0, + load_knn_one/0, + load_knn_two/0 ]). :- rdf_meta @@ -522,4 +524,10 @@ load_annotator_setup(I, 'SetupCylinder'). test_overwrite_param:- - cpp_overwrite_param('SacModelAnnotator', 'sacModel', ['CYLINDER']). \ No newline at end of file + cpp_overwrite_param('SacModelAnnotator', 'sacModel', ['CYLINDER']). + +load_knn_one:- + cpp_reconfigure_annotator('KnnAnnotator', 'setup_one'). + +load_knn_two:- + cpp_reconfigure_annotator('KnnAnnotator', 'setup_two'). diff --git a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp index ac3fe86e..0a4c219e 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -370,6 +370,9 @@ bool RSAggregateAnalysisEngine::reconfigureAnnotator(int annotatorIdx) { if(annotatorIdx >= 0 && annotatorIdx < iv_annotatorMgr.iv_vecEntries.size()) { return iv_annotatorMgr.iv_vecEntries[annotatorIdx].iv_pEngine->reconfigure() == UIMA_ERR_NONE; } + else { + outError("Annotator index is invalid."); + } return false; } diff --git a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp index d35c4bcb..aaa93dfb 100644 --- a/robosherlock/src/flowcontrol/src/RSProcessManager.cpp +++ b/robosherlock/src/flowcontrol/src/RSProcessManager.cpp @@ -615,6 +615,9 @@ bool RSProcessManager::handleReconfigureAnnotator(robosherlock_msgs::Reconfigure outInfo("Loading setup \"" << req.setupName << "\" for the annotator \"" << req.annotatorName << "\"."); res.result = engine_->reconfigureAnnotator(req.annotatorName); + + // TODO: Remove it + engine_->reconfigure(); } else { outError("The requested setup \"" << req.setupName << "\" for the annotator \"" << req.annotatorName << "\" could not be found."); diff --git a/robosherlock/src/flowcontrol/src/run.cpp b/robosherlock/src/flowcontrol/src/run.cpp index cee5dbb6..499744c7 100644 --- a/robosherlock/src/flowcontrol/src/run.cpp +++ b/robosherlock/src/flowcontrol/src/run.cpp @@ -80,7 +80,7 @@ int main(int argc, char* argv[]) return 1; } - ros::init(argc, argv, std::string("RoboSherlock_") + getenv("USER")); + ros::init(argc, argv, std::string("RoboSherlock")); if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug)) { diff --git a/robosherlock/src/flowcontrol/src/runAAE.cpp b/robosherlock/src/flowcontrol/src/runAAE.cpp index 3d545e18..d7485e33 100644 --- a/robosherlock/src/flowcontrol/src/runAAE.cpp +++ b/robosherlock/src/flowcontrol/src/runAAE.cpp @@ -81,7 +81,7 @@ int main(int argc, char* argv[]) return 1; } - ros::init(argc, argv, std::string("RoboSherlock_") + getenv("USER")); + ros::init(argc, argv, std::string("RoboSherlock")); if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) ros::console::notifyLoggerLevelsChanged(); diff --git a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp index 90f9ea6b..6eef8284 100644 --- a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp +++ b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp @@ -211,7 +211,8 @@ PREDICATE(cpp_reconfigure_annotator, 2) setupName = (std::string) PL_A2; ros::NodeHandle n; - ros::ServiceClient client = n.serviceClient(std::string("RoboSherlock_") + getenv("USER") + "/reconfigure_annotator"); + // TODO: Change to nodename String name + ros::ServiceClient client = n.serviceClient("RoboSherlock/reconfigure_annotator"); robosherlock_msgs::ReconfigureAnnotator srv; srv.request.annotatorName = annotatorName; @@ -237,7 +238,8 @@ PREDICATE(cpp_overwrite_param, 3) values = (std::vector) PL_A3; ros::NodeHandle n; - ros::ServiceClient client = n.serviceClient(std::string("RoboSherlock_") + getenv("USER") + "/overwrite_param"); + // TODO: Change to nodename String name + ros::ServiceClient client = n.serviceClient("RoboSherlock/overwrite_param"); robosherlock_msgs::OverwriteParam srv; srv.request.annotatorName = annotatorName; diff --git a/uimacpp_ros/src/framework/include/uima/annotator_abase.hpp b/uimacpp_ros/src/framework/include/uima/annotator_abase.hpp index 29d610b5..86b505bd 100644 --- a/uimacpp_ros/src/framework/include/uima/annotator_abase.hpp +++ b/uimacpp_ros/src/framework/include/uima/annotator_abase.hpp @@ -41,6 +41,7 @@ #include // must be first file to be included to get pragmas ////#include "uima/annotator_api.h" #include +#include /* ----------------------------------------------------------------------- */ /* Constants */ @@ -177,6 +178,7 @@ namespace uima { } inline TyErrorId Annotator::reconfigure() { + std::cout << "\n\nCalling base reconfigure()\n\n"; return (TyErrorId)UIMA_ERR_NONE; } From d88c4c507ec2c4d8a0fe0f690395d52491852218 Mon Sep 17 00:00:00 2001 From: Evan Kapitzke Date: Thu, 4 Jun 2020 17:24:11 +0200 Subject: [PATCH 13/13] Restore original cmake files --- robosherlock/cmake/FindAPR.cmake | 30 ++++ robosherlock/cmake/FindICUUC.cmake | 23 +++ .../cmake/FindMongoClientLibrary.cmake | 31 ++++ robosherlock/cmake/project_config.cmake.in | 6 + robosherlock/cmake/robosherlock.cmake | 152 ++++++++++++++++++ .../cmake/robosherlock_config.cmake.em | 17 ++ 6 files changed, 259 insertions(+) create mode 100644 robosherlock/cmake/FindAPR.cmake create mode 100644 robosherlock/cmake/FindICUUC.cmake create mode 100644 robosherlock/cmake/FindMongoClientLibrary.cmake create mode 100644 robosherlock/cmake/project_config.cmake.in create mode 100644 robosherlock/cmake/robosherlock.cmake create mode 100644 robosherlock/cmake/robosherlock_config.cmake.em diff --git a/robosherlock/cmake/FindAPR.cmake b/robosherlock/cmake/FindAPR.cmake new file mode 100644 index 00000000..30bf6233 --- /dev/null +++ b/robosherlock/cmake/FindAPR.cmake @@ -0,0 +1,30 @@ +# APR_LIBRARY_FOUND - system has Mongo Client +# APR_LIBRARY - Mongo Client Library +# APR_INCLUDE_DIR - Mongo Client Library + +find_package(PkgConfig) +pkg_check_modules(PC_LIBAPR QUIET apr-1) +set(LIBAPR_DEFINITIONS ${PC_LIBAPR_CFLAGS_OTHER}) + +find_path(LIBAPR_INCLUDE_DIR + apr.h + HINTS ${PC_LIBAPR_INCLUDEDIR} ${PC_LIBAPR_INCLUDE_DIRS} + DOC "Found LIBAPR include directory" +) + +find_library(LIBAPR_LIBRARY + NAMES apr-1.0 apr-1 libapr-1.0 libapr-1 + HINTS ${PC_LIBAPR_LIBDIR} ${PC_LIBAPR_LIBRARY_DIRS} + DOC "Found LIBAPR library" +) + +set(LIBAPR_LIBRARIES ${LIBAPR_LIBRARY} ) +set(LIBAPR_INCLUDE_DIRS ${LIBAPR_INCLUDE_DIR} ) + +include(FindPackageHandleStandardArgs) +# handle the QUIETLY and REQUIRED arguments and set LIBXML2_FOUND to TRUE +# if all listed variables are TRUE +find_package_handle_standard_args(LibAPR1 DEFAULT_MSG + LIBAPR_LIBRARY LIBAPR_INCLUDE_DIR) + +mark_as_advanced(LIBAPR_INCLUDE_DIR LIBAPR_LIBRARY ) diff --git a/robosherlock/cmake/FindICUUC.cmake b/robosherlock/cmake/FindICUUC.cmake new file mode 100644 index 00000000..bc771646 --- /dev/null +++ b/robosherlock/cmake/FindICUUC.cmake @@ -0,0 +1,23 @@ +# ICUUC_LIBRARY_FOUND - system has ICUUC +# ICUUC_LIBRARY - ICUUC Library + +find_library(ICUUC_LIB + NAMES libicuuc.so + DOC "Found ICUUC library" + PATHS /usr/local/lib +) + +if(ICUUC_LIB) + set(ICUUC_LIBRARY ${ICUUC_LIB}) + set(ICUUC_LIBRARIES ${ICUUC_LIB}) + message(STATUS "Found ICUUC Library: ${ICUUC_LIB}") + set(ICUUC_LIBRARY_FOUND true) +else() + set(ICUUC_LIBRARY_FOUND false) + if(ICUUC_LIBRARY_FIND_REQUIRED) + message(FATAL_ERROR "ICUUC library not found!") + else() + message(STATUS "ICUUC library not found!") + endif() +endif() + diff --git a/robosherlock/cmake/FindMongoClientLibrary.cmake b/robosherlock/cmake/FindMongoClientLibrary.cmake new file mode 100644 index 00000000..c1a57cbc --- /dev/null +++ b/robosherlock/cmake/FindMongoClientLibrary.cmake @@ -0,0 +1,31 @@ +# MONGO_CLIENT_LIBRARY_FOUND - system has Mongo Client +# MONGO_CLIENT_LIBRARY - Mongo Client Library + +message(STATUS "Looking for Mongo Client Library...") + +find_library(MONGO_CLIENT_LIBRARY + NAMES libmongoclient.so + DOC "Found MONGO library" + PATHS /usr/local/lib +) + +if(MONGO_CLIENT_LIBRARY) + set(MONGO_CLIENT_LIBRARY_FOUND 1) + + if(NOT MONGO_CLIENT_LIBRARY_FIND_QUIETLY) + message(STATUS "Found Mongo CLient Library: ${MONGO_CLIENT_LIBRARY}") + endif(NOT MONGO_CLIENT_LIBRARY_FIND_QUIETLY) + +else(MONGO_CLIENT_LIBRARY) + + set(MONGO_CLIENT_LIBRARY_FOUND 0 CACHE BOOL "Mongo Client Library not found") + if(MONGO_CLIENT_LIBRARY_FIND_REQUIRED) + message(FATAL_ERROR "Mongo Client Library not found, error") + else() + MESSAGE(STATUS "Mongo Client Library not found, disabled") + endif() +endif(MONGO_CLIENT_LIBRARY) + +MARK_AS_ADVANCED(MONGO_CLIENT_LIBRARY) + + diff --git a/robosherlock/cmake/project_config.cmake.in b/robosherlock/cmake/project_config.cmake.in new file mode 100644 index 00000000..2e5b1896 --- /dev/null +++ b/robosherlock/cmake/project_config.cmake.in @@ -0,0 +1,6 @@ +set(${PROJECT_NAME}_NAMESPACE ${NAMESPACE}) +set(${PROJECT_NAME}_TYPESYSTEM_CPP_PATH ${TYPESYSTEM_CPP_PATH}) +set(${PROJECT_NAME}_TYPESYSTEM_XML_PATH ${TYPESYSTEM_XML_PATH}) +set(${PROJECT_NAME}_ANNOTATOR_PATH ${ANNOTATOR_PATH}) +set(${PROJECT_NAME}_ENGINE_PATH ${ENGINE_PATH}) + diff --git a/robosherlock/cmake/robosherlock.cmake b/robosherlock/cmake/robosherlock.cmake new file mode 100644 index 00000000..e72a8103 --- /dev/null +++ b/robosherlock/cmake/robosherlock.cmake @@ -0,0 +1,152 @@ + +############################################################################# +## Check for c++11 support ## +############################################################################# +include(CheckCXXCompilerFlag) +check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +else() + message(ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") +endif() + +############################################################################# +## Set cxx flags ## +############################################################################# +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DBT_USE_DOUBLE_PRECISION -Wno-deprecated") +# Unused warnings +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wuninitialized -Winit-self -Wunused-function -Wunused-label -Wunused-variable -Wunused-but-set-parameter")#-Wunused-but-set-variable +# Additional warnings +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wreorder -Warray-bounds -Wtype-limits -Wreturn-type -Wsequence-point -Wparentheses -Wmissing-braces -Wchar-subscripts -Wswitch -Wwrite-strings -Wenum-compare -Wempty-body")# -Wlogical-op") + +############################################################################# +## Check for openMP support ## +############################################################################# +find_package(OpenMP) +if(OPENMP_FOUND) + message(STATUS "OpenMP found.") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") +endif() + + +############################################################################# +## Check for Caffe Support ## +############################################################################# +find_package(Caffe QUIET) +if(Caffe_FOUND) + message(STATUS "Caffe FOUND! Building related components") + + include_directories(${Caffe_INCLUDE_DIRS}) + add_definitions( -DCAFFE_FOUND ${Caffe_DEFINITIONS}) + + set(RS_CAFFE_LIB rs_caffeProxy) + set(RS_WITH_CAFFE TRUE) +else() + set(RS_WITH_CAFFE FALSE) +endif(Caffe_FOUND) + + +############################################################################# +## Check for Protobuf Support ## +############################################################################# +find_package(Protobuf QUIET) +if(PROTOBUF_FOUND AND PROTOBUF_PROTOC_EXECUTABLE) + message (STATUS "Found Protobuf and Protobuf executable.") + set(RS_WEB_LIB rs_web) + set(RS_WITH_GG TRUE) +else() + set(RS_WITH_GG FALSE) +endif() + + +############################################################################# +## Adding include dirs defined in CPATH (needed for xstow) ## +############################################################################# +if($ENV{CPATH}) + string(REPLACE ":" ";" paths $ENV{CPATH}) + foreach(path ${paths}) + include_directories(${path}) + endforeach() +endif() + +############################################################################# +## Add library macro ## +############################################################################# +macro(rs_add_library libname) + add_library(${libname} SHARED ${ARGN}) + target_link_libraries(${libname} ${LIBAPR_LIBRARY} ${UIMA_LIBRARY} ${ICUUC_LIBRARY} ${catkin_LIBRARIES}) + set_target_properties(${libname} PROPERTIES PREFIX "") +endmacro(rs_add_library) + +############################################################################# +## Add executable macro ## +############################################################################# +macro(rs_add_executable execname) + add_executable(${execname} ${ARGN}) + target_link_libraries(${execname} ${LIBAPR_LIBRARY} ${UIMA_LIBRARY} ${ICUUC_LIBRARY} ${catkin_LIBRARIES}) +endmacro(rs_add_executable) + +############################################################################# +## Generate classes from the typesystem xml files ## +############################################################################# +macro(generate_type_system) + set(script ${RS_SCRIPT_PATH}/generate_typesystem.py) + set(projects ${PROJECT_NAME}:${NAMESPACE}:${TYPESYSTEM_XML_PATH}:${TYPESYSTEM_CPP_PATH}) + + foreach(arg ${ARGN}) + set(projects ${projects} ${arg}:${${arg}_NAMESPACE}:${${arg}_TYPESYSTEM_XML_PATH}:${${arg}_TYPESYSTEM_CPP_PATH}) + endforeach() + + execute_process(COMMAND python ${script} ${projects}) +endmacro(generate_type_system) + +############################################################################# +## Find all include directories for export ## +############################################################################# +macro(find_include_dirs result) + set(search_pattern -name "include" -type d) + + foreach(arg ${ARGN}) + set(exclude ${exclude} ! -path "${PROJECT_SOURCE_DIR}/${arg}/*") + endforeach() + + message(STATUS "find path: ${PROJECT_SOURCE_DIR}/${arg}") + + execute_process(COMMAND find "-L" ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern} OUTPUT_VARIABLE found_include_dirs) + message(STATUS "executed: find ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern}") + + message(STATUS "found include path: ${found_include_dirs}") + + if(NOT "${found_include_dirs}" STREQUAL "") + string(REPLACE "\n" "/\;" ${result} ${found_include_dirs}) + #message(STATUS "additional include dirs: ${${result}}") + endif() +endmacro(find_include_dirs) + +############################################################################# +## Hack for QT Creator to include all relevant files ## +############################################################################# +macro(find_additional_files) + set(search_pattern -type f) + + foreach(arg ${ARGN}) + set(exclude ${exclude} ! -path "${PROJECT_SOURCE_DIR}/${arg}/*") + endforeach() + execute_process(COMMAND find "-L" ${PROJECT_SOURCE_DIR} ${exclude} ${search_pattern} OUTPUT_VARIABLE found_files) + if(NOT "${found_files}" STREQUAL "") + string(REPLACE "\n" ";" found_files_list ${found_files}) + add_custom_target(${PROJECT_NAME}_additional_files SOURCES ${found_files_list}) + endif() +endmacro(find_additional_files) + +############################################################################# +## Message on option status ## +############################################################################# +macro(check_option var) + if(${var}) + message(STATUS "${var} activated") + else(${var}) + message(STATUS "${var} deactivated") + endif(${var}) +endmacro(check_option) + diff --git a/robosherlock/cmake/robosherlock_config.cmake.em b/robosherlock/cmake/robosherlock_config.cmake.em new file mode 100644 index 00000000..3827aa70 --- /dev/null +++ b/robosherlock/cmake/robosherlock_config.cmake.em @@ -0,0 +1,17 @@ +set(robosherlock_NAMESPACE rs) +@[if DEVELSPACE]@ + +set(robosherlock_TYPESYSTEM_CPP_PATH "@(PROJECT_SOURCE_DIR)/src/core/include/robosherlock/types") +set(robosherlock_TYPESYSTEM_XML_PATH "@(PROJECT_SOURCE_DIR)/descriptors/typesystem") +set(robosherlock_ANNOTATOR_PATH "@(PROJECT_SOURCE_DIR)/descriptors/annotators") +set(robosherlock_ENGINE_PATH "@(PROJECT_SOURCE_DIR)/descriptors/analysis_engines") +set(RS_SCRIPT_PATH "@(PROJECT_SOURCE_DIR)/scripts") +set(RS_PROJECT_CONFIG "@(PROJECT_SOURCE_DIR)/cmake/project_config.cmake.in") +@[else]@ +set(robosherlock_TYPESYSTEM_CPP_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_INCLUDE_DESTINATION)/types") +set(robosherlock_TYPESYSTEM_XML_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/typesystem") +set(robosherlock_ANNOTATOR_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/annotators") +set(robosherlock_ENGINE_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/descriptors/analysis_engines") +set(RS_SCRIPT_PATH "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/scripts") +set(RS_PROJECT_CONFIG "${robosherlock_PREFIX}/@(CATKIN_PACKAGE_SHARE_DESTINATION)/cmake/project_config.cmake.in") +@[end if]@