diff --git a/robosherlock/config/config_reconfig_demo.ini b/robosherlock/config/config_reconfig_demo.ini new file mode 100644 index 00000000..7c033644 --- /dev/null +++ b/robosherlock/config/config_reconfig_demo.ini @@ -0,0 +1,12 @@ +[camera] +interface=MongoDB + +[mongodb] +host=localhost +db=classification_test_table +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 new file mode 100644 index 00000000..ef04a229 --- /dev/null +++ b/robosherlock/descriptors/analysis_engines/reconfig_demo.yaml @@ -0,0 +1,26 @@ +ae: + name: demo +fixedflow: + - CollectionReader + - ImagePreprocessor + - PointCloudFilter + - NormalEstimator + - PlaneAnnotator + - 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/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 95aef3fd..a8ae274f 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,29 @@ parameters: minPoints: 200 radiusLimit1: 0.01 radiusLimit2: 0.5 - sacModel: 6 + sacModel: "CYLINDER" useNormals: true + +reconfiguration: + # Definition of sphere reconfiguration + setup_spheres: + capabilities: + outputs: + - rs.annotation.Shape: [sphere] + domain: [sphere] + + # Overwrite or define new parameters: + parameters: + distanceThreshold: 0.10 + sacModel: "SPHERE" + + # Example setup + setup_cylinder: + capabilities: + outputs: + - rs.annotation.Shape: [cylinder] + 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 77d18d3b..daff8267 100644 --- a/robosherlock/prolog/rs_query_reasoning.pl +++ b/robosherlock/prolog/rs_query_reasoning.pl @@ -42,7 +42,14 @@ 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, + load_sphere_setup/0, + find_sphere_setup/2, + test_overwrite_param/0, + load_knn_one/0, + load_knn_two/0 ]). :- rdf_meta @@ -56,9 +63,22 @@ 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). +:- use_foreign_library('librs_prologQueries.so'). + %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% % Pipeline Planning @@ -68,12 +88,12 @@ compute_annotators(A) :- owl_subclass_of(A,rs_components:'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'). + 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 @@ -369,7 +389,7 @@ 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,rs_components:'Box')). @@ -422,3 +442,92 @@ retract_query_assertions:- retract(requestedValueForKey(_,_)). +%% Reconfiguration Rules + +assert_reconfiguration_pipeline:- + assert_test_pipeline, + owl_individual_of(I, rs_components:'SacModelAnnotator'), + set_annotator_setup_names(I, ['SetupCylinder', 'SetupSphere']), + 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) :- + 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), + 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), + 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), + 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) :- + 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, rs_components:'RsAnnotationShape', [rs_components:'Sphere']). + +load_sphere_setup:- + cpp_reconfigure_annotator('SacModelAnnotator', 'setup_spheres'). + +load_cylinder_setup:- + owl_individual_of(I,rs_components:'SacModelAnnotator'), + load_annotator_setup(I, 'SetupCylinder'). + +test_overwrite_param:- + 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/annotation/src/SacModelAnnotator.cpp b/robosherlock/src/annotation/src/SacModelAnnotator.cpp index 68be7004..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; @@ -44,89 +44,124 @@ 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")) + { + 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; + } + + 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 +179,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..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 { /** @@ -57,9 +78,16 @@ struct AnnotatorCapabilities * @brief iTypeValueRestrictions mapping between input type and possible values (if no restrictions on values vector is empty) */ std::map> iTypeValueRestrictions; + /** + * @brief The default setup + */ + AnnotatorSetup defaultSetup; + /** + * @brief Contains all setups for this annotator + */ + 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 74879435..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,55 @@ 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 + * @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); + // 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 8185c1bf..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_; @@ -145,6 +147,12 @@ class RSProcessManager */ bool resetAE(std::string); + bool handleReconfigureAnnotator(robosherlock_msgs::ReconfigureAnnotator::Request &req, + robosherlock_msgs::ReconfigureAnnotator::Response &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 d0b73913..4831ed8b 100644 --- a/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h +++ b/robosherlock/src/flowcontrol/include/robosherlock/flowcontrol/YamlToXMLConverter.h @@ -126,22 +126,24 @@ class YamlToXMLConverter string getType(const YAML::Node& node); string getTypeFilePath() const; - 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..0a4c219e 100644 --- a/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp +++ b/robosherlock/src/flowcontrol/src/RSAggregateAnalysisEngine.cpp @@ -366,6 +366,21 @@ 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; + } + else { + outError("Annotator index is invalid."); + } + + return false; +} + +bool RSAggregateAnalysisEngine::reconfigureAnnotator(std::string &annotatorName) { + return reconfigureAnnotator(getIndexOfAnnotator(std::move(annotatorName))); +} + namespace rs { std::string convertAnnotatorYamlToXML(std::string annotator_name, @@ -394,6 +409,9 @@ std::string convertAnnotatorYamlToXML(std::string annotator_name, if (delegate_capabilities[annotator_name].iTypeValueRestrictions.empty()) delegate_capabilities[annotator_name].iTypeValueRestrictions = converter.getAnnotatorCapabilities().iTypeValueRestrictions; + + 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 06670266..aaa93dfb 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 @@ -45,6 +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); @@ -573,6 +575,85 @@ bool RSProcessManager::highlightResultsInCloud(const std::vector &filter, return true; } +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() on \"" << 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; + 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); + + // TODO: Remove it + engine_->reconfigure(); + } + 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."); + res.result = false; + } + } + return res.result; +} + +bool RSProcessManager::handleOverwriteParam(robosherlock_msgs::OverwriteParam::Request &req, + robosherlock_msgs::OverwriteParam::Response &res) { + 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 res.result; + } +} + 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..f3785640 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) != "") { @@ -184,37 +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; -} - bool YamlToXMLConverter::parseAnnotatorInfo(const YAML::Node &node) { if(node.Type() == YAML::NodeType::Map) @@ -491,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 { @@ -549,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 { @@ -638,10 +618,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 +642,14 @@ 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 + { + annotCap.reconfigurationSetups[setup_name].rInputTypeValueRestrictions[val] = std::vector(); + } } if(sit->Type() == YAML::NodeType::Map) { @@ -674,13 +660,21 @@ 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 + { + annotCap.reconfigurationSetups[setup_name].rInputTypeValueRestrictions[val] = 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 +696,13 @@ 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 + { + annotCap.reconfigurationSetups[setup_name].rOutputTypeValueDomains[val] = std::vector(); + } } if(n.Type() == YAML::NodeType::Map) { @@ -713,8 +713,14 @@ 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 + { + annotCap.reconfigurationSetups[setup_name].rOutputTypeValueDomains[val] = e.second.as>(); + } } } } @@ -784,3 +790,86 @@ 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(); + + 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) + { + string node_name = sit->first.as(); + + 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) + { + 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 + { + 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/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/include/robosherlock/queryanswering/KnowledgeEngine.h b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h index c6ed3dc1..20a26563 100644 --- a/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h +++ b/robosherlock/src/queryanswering/include/robosherlock/queryanswering/KnowledgeEngine.h @@ -169,6 +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; + // TODO: Get info from RSAnnotatorSetup object if(!inputRestrictions.empty()) { @@ -239,6 +242,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 diff --git a/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp b/robosherlock/src/queryanswering/src/PrologCPPQueries.cpp index c2487f7c..6eef8284 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,56 @@ PREDICATE(write_list, 1) } return TRUE; } + + +PREDICATE(cpp_reconfigure_annotator, 2) +{ + std::string annotatorName, setupName; + annotatorName = (std::string) PL_A1; + setupName = (std::string) PL_A2; + + ros::NodeHandle n; + // TODO: Change to nodename String name + 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 reconfigure_annotator was successful" << std::endl; + return TRUE; + } + else { + std::cerr << "Service call reconfigure_annotator failed!" << std::endl; + return FALSE; + } +} + + +PREDICATE(cpp_overwrite_param, 3) +{ + 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; + // TODO: Change to nodename String name + ros::ServiceClient client = n.serviceClient("RoboSherlock/overwrite_param"); + robosherlock_msgs::OverwriteParam srv; + + srv.request.annotatorName = annotatorName; + srv.request.parameterName = paramName; + srv.request.values = values; + + if(client.call(srv)) { + std::cout << "Calling overwrite_param was successful" << std::endl; + return TRUE; + } + else { + std::cerr << "Service call overwrite_param failed!" << std::endl; + return FALSE; + } +} \ No newline at end of file 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..32b9683f --- /dev/null +++ b/robosherlock_msgs/srv/OverwriteParam.srv @@ -0,0 +1,9 @@ +string annotatorName +string parameterName +string[] values + +--- +bool result + + + 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 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; }