plannerParameters.cpp
Go to the documentation of this file.
00001 #include "plannerParameters.h"
00002 #include <iostream>
00003 #if ROS_BUILD
00004 #include <ros/ros.h>
00005 #endif
00006 #include <stdio.h>
00007 
00008 PlannerParameters::PlannerParameters()
00009 {
00010     // set defaults
00011     anytime_search = false;
00012     disallow_concurrent_actions = false;
00013     timeout_while_no_plan_found = 0;
00014     timeout_if_plan_found = 0;
00015     min_search_time_after_plan_found = 0;
00016     min_search_time_factor_after_plan_found = 0.0;
00017 
00018     greedy = false;
00019     lazy_evaluation = true;
00020     verbose = true;
00021 
00022     insert_let_time_pass_only_when_running_operators_not_empty = false;
00023 
00024     lazy_state_module_evaluation = -1;
00025     use_cost_modules_for_applicability = true;
00026 
00027     cyclic_cg_heuristic = false;
00028     cyclic_cg_preferred_operators = false;
00029     makespan_heuristic = false;
00030     makespan_heuristic_preferred_operators = false;
00031     no_heuristic = false;
00032 
00033     cg_heuristic_zero_cost_waiting_transitions = true;
00034     cg_heuristic_fire_waiting_transitions_only_if_local_problems_matches_state = false;
00035 
00036     g_values = GTimestamp;
00037     g_weight = 0.5;
00038 
00039     queueManagementMode = BestFirstSearchEngine::PRIORITY_BASED;
00040 
00041     use_known_by_logical_state_only = false;
00042 
00043     use_subgoals_to_break_makespan_ties = false;
00044 
00045     reschedule_plans = false;
00046     epsilonize_internally = false;
00047     epsilonize_externally = false;
00048     keep_original_plans = true;
00049 
00050     plan_name = "sas_plan";
00051     planMonitorFileName = "";
00052 
00053     monitoring_verify_timestamps = false;
00054 }
00055 
00056 PlannerParameters::~PlannerParameters()
00057 {
00058 }
00059 
00060 bool PlannerParameters::readParameters(int argc, char** argv)
00061 {
00062     bool ret = true;
00063     ret &= readROSParameters();
00064     ret &= readCmdLineParameters(argc, argv);
00065 
00066     if(!cyclic_cg_heuristic && !makespan_heuristic && !no_heuristic) {
00067         if(planMonitorFileName.empty()) {   // for monitoring this is irrelevant
00068             cerr << "Error: you must select at least one heuristic!" << endl
00069                 << "If you are unsure, choose options \"yY\" / cyclic_cg_heuristic." << endl;
00070             ret = false;
00071         }
00072     }
00073     if(timeout_if_plan_found < 0) {
00074         cerr << "Error: timeout_if_plan_found < 0, have: " << timeout_if_plan_found << endl;
00075         timeout_if_plan_found = 0;
00076         ret = false;
00077     }
00078     if(timeout_while_no_plan_found < 0) {
00079         cerr << "Error: timeout_while_no_plan_found < 0, have: " << timeout_while_no_plan_found << endl;
00080         timeout_while_no_plan_found = 0;
00081         ret = false;
00082     }
00083     if(min_search_time_after_plan_found < 0) {
00084         cerr << "Error: min_search_time_after_plan_found < 0, have: " << min_search_time_after_plan_found << endl;
00085         min_search_time_after_plan_found = 0;
00086         ret = false;
00087     }
00088     if(min_search_time_factor_after_plan_found < 0.0) {
00089         cerr << "Error: min_search_time_factor_after_plan_found < 0, have: " << min_search_time_factor_after_plan_found << endl;
00090         min_search_time_factor_after_plan_found = 0.0;
00091         ret = false;
00092     }
00093     if(use_known_by_logical_state_only) {
00094         cerr << "WARNING: known by logical state only is experimental and might lead to incompleteness!" << endl;
00095     }
00096 
00097     return ret;
00098 }
00099 
00100 void PlannerParameters::dump() const
00101 {
00102     cout << endl << "Planner Paramters:" << endl;
00103     cout << "Anytime Search: " << (anytime_search ? "Enabled" : "Disabled") << endl;
00104     cout << "Disallow concurrent actions: " << (disallow_concurrent_actions ? "Enabled" : "Disabled") << endl;
00105     if(disallow_concurrent_actions)
00106         cout << "WARNING: planning non-temporally" << endl;
00107     cout << "Timeout if plan was found: " << timeout_if_plan_found << " seconds";
00108     if(timeout_if_plan_found == 0)
00109         cout << " (no timeout)";
00110     cout << endl;
00111     cout << "Timeout while no plan was found: " << timeout_while_no_plan_found << " seconds";
00112     if(timeout_while_no_plan_found == 0)
00113         cout << " (no timeout)";
00114     cout << endl;
00115     cout << "Min search time after plan found: " << min_search_time_after_plan_found << " seconds" << endl;
00116     cout << "Min search time factor after plan found: " << min_search_time_factor_after_plan_found << " seconds" << endl;
00117     cout << "Greedy Search: " << (greedy ? "Enabled" : "Disabled") << endl;
00118     cout << "Verbose: " << (verbose ? "Enabled" : "Disabled") << endl;
00119     cout << "Lazy Heuristic Evaluation: " << (lazy_evaluation ? "Enabled" : "Disabled") << endl;
00120     cout << "Lazy State Module Evaluation: " << lazy_state_module_evaluation;
00121     if(lazy_state_module_evaluation < 0)
00122         cout << " (auto)";
00123     cout << endl;
00124     cout << "Use cost modules for applicablity: "
00125         << (use_cost_modules_for_applicability ? "Enabled" : "Disabled") << endl;
00126 
00127     cout << "Cyclic CG heuristic: " << (cyclic_cg_heuristic ? "Enabled" : "Disabled")
00128         << " \tPreferred Operators: " << (cyclic_cg_preferred_operators ? "Enabled" : "Disabled") << endl;
00129     cout << "Makespan heuristic: " << (makespan_heuristic ? "Enabled" : "Disabled")
00130         << " \tPreferred Operators: " << (makespan_heuristic_preferred_operators ? "Enabled" : "Disabled") << endl;
00131     cout << "No Heuristic: " << (no_heuristic ? "Enabled" : "Disabled") << endl;
00132     cout << "Cg Heuristic Zero Cost Waiting Transitions: "
00133         << (cg_heuristic_zero_cost_waiting_transitions ? "Enabled" : "Disabled") << endl;
00134     cout << "Cg Heuristic Fire Waiting Transitions Only If Local Problems Matches State: "
00135         << (cg_heuristic_fire_waiting_transitions_only_if_local_problems_matches_state ? "Enabled" : "Disabled") << endl;
00136 
00137     cout << "GValues by: ";
00138     switch(g_values) {
00139         case GMakespan:
00140             cout << "Makespan";
00141             break;
00142         case GCost:
00143             cout << "Cost";
00144             break;
00145         case GTimestamp:
00146             cout << "Timestamp";
00147             break;
00148         case GWeighted:
00149             cout << "Weighted (" << g_weight << ")";
00150             break;
00151     }
00152     cout << endl;
00153 
00154     cout << "Queue management mode: ";
00155     switch(queueManagementMode) {
00156         case BestFirstSearchEngine::PRIORITY_BASED:
00157             cout << "Priority based";
00158             break;
00159         case BestFirstSearchEngine::ROUND_ROBIN:
00160             cout << "Round Robin";
00161             break;
00162     }
00163     cout << endl;
00164 
00165     cout << "Known by logical state only filtering: "
00166         << (use_known_by_logical_state_only ? "Enabled" : "Disabled") << endl;
00167 
00168     cout << "use_subgoals_to_break_makespan_ties: "
00169         << (use_subgoals_to_break_makespan_ties ? "Enabled" : "Disabled") << endl;
00170 
00171     cout << "Reschedule plans: " << (reschedule_plans ? "Enabled" : "Disabled") << endl;
00172     cout << "Epsilonize internally: " << (epsilonize_internally ? "Enabled" : "Disabled") << endl;
00173     cout << "Epsilonize externally: " << (epsilonize_externally ? "Enabled" : "Disabled") << endl;
00174     cout << "Keep original plans: " << (keep_original_plans ? "Enabled" : "Disabled") << endl;
00175 
00176     cout << "Plan name: \"" << plan_name << "\"" << endl;
00177     cout << "Plan monitor file: \"" << planMonitorFileName << "\"";
00178     if(planMonitorFileName.empty()) {
00179         cout << " (no monitoring)";
00180     }
00181     cout << endl;
00182 
00183     cout << "Monitoring verify timestamps: " << (monitoring_verify_timestamps ? "Enabled" : "Disabled") << endl;
00184 
00185     cout << endl;
00186 }
00187 
00188 bool PlannerParameters::readROSParameters()
00189 {
00190     bool ret = true;
00191 
00192 #if ROS_BUILD
00193     ros::NodeHandle nhPriv("~");
00194     nhPriv.param("anytime_search", anytime_search, anytime_search);
00195     nhPriv.param("disallow_concurrent_actions", disallow_concurrent_actions, disallow_concurrent_actions);
00196     nhPriv.param("timeout_if_plan_found", timeout_if_plan_found, timeout_if_plan_found);
00197     nhPriv.param("timeout_while_no_plan_found", timeout_while_no_plan_found, timeout_while_no_plan_found); 
00198     nhPriv.param("min_search_time_after_plan_found",
00199             min_search_time_after_plan_found, min_search_time_after_plan_found);
00200     nhPriv.param("min_search_time_factor_after_plan_found",
00201             min_search_time_factor_after_plan_found, min_search_time_factor_after_plan_found);
00202 
00203     nhPriv.param("greedy", greedy, greedy);
00204     nhPriv.param("lazy_evaluation", lazy_evaluation, lazy_evaluation);
00205 
00206     nhPriv.param("lazy_state_module_evaluation", lazy_state_module_evaluation, lazy_state_module_evaluation);
00207     nhPriv.param("use_cost_modules_for_applicability", use_cost_modules_for_applicability, use_cost_modules_for_applicability);
00208 
00209     nhPriv.param("cyclic_cg_heuristic", cyclic_cg_heuristic, cyclic_cg_heuristic);
00210     nhPriv.param("cyclic_cg_heuristic_preferred_operators", 
00211             cyclic_cg_preferred_operators, cyclic_cg_preferred_operators);
00212     nhPriv.param("makespan_heuristic", makespan_heuristic, makespan_heuristic);
00213     nhPriv.param("makespan_heuristic_preferred_operators", makespan_heuristic_preferred_operators, 
00214             makespan_heuristic_preferred_operators);
00215     nhPriv.param("no_heuristic", no_heuristic, no_heuristic);
00216 
00217     string gMode;
00218     if(nhPriv.getParam("g_values", gMode)) {
00219         if(gMode == "makespan") {
00220             g_values = GMakespan;
00221         } else if(gMode == "cost") {
00222             g_values = GCost;
00223         } else if(gMode == "timestamp") {
00224             g_values = GTimestamp;
00225         } else if(gMode == "weighted") {
00226             g_values = GWeighted;
00227             if(!nhPriv.getParam("g_weight", g_weight)) {
00228                 ROS_FATAL("G mode weighted choosen, but g_weight not set.");
00229                 ret = false;
00230             }
00231         } else {
00232             ROS_FATAL("Unknown value: %s for g_values. Valid values: [makespan, cost, timestamp, weighted]", gMode.c_str());
00233             ret = false;
00234         }
00235     }
00236 
00237     string qMode;
00238     if(nhPriv.getParam("queue_management_mode", qMode)) {
00239         if(qMode == "priority_based") {
00240             queueManagementMode = BestFirstSearchEngine::PRIORITY_BASED;
00241         } else if(qMode == "round_robin") {
00242             queueManagementMode = BestFirstSearchEngine::ROUND_ROBIN;
00243         } else {
00244             ROS_FATAL("Unknown value: %s for queue management mode. Valid values: [priority_based, round_robin, hierarchical]", qMode.c_str());
00245             ret = false;
00246         }
00247     }
00248 
00249     nhPriv.param("use_known_by_logical_state_only",
00250             use_known_by_logical_state_only, use_known_by_logical_state_only);
00251 
00252     nhPriv.param("reschedule_plans", reschedule_plans, reschedule_plans);
00253     nhPriv.param("plan_name", plan_name, plan_name);
00254 
00255     // Don't get planMonitorFileName from param server as that is an input
00256 
00257     nhPriv.param("monitoring_verify_timestamps", monitoring_verify_timestamps, monitoring_verify_timestamps);
00258 #endif
00259 
00260     return ret;
00261 }
00262 
00263 void PlannerParameters::printUsage() const
00264 {
00265     printf("Usage: search <option characters>  (input read from stdin)\n");
00266     printf("Options are:\n");
00267     printf("  a - enable anytime search (otherwise finish on first plan found)\n");
00268     printf("  c - disallow any concurrent actions (plan classically, NOT temporal)\n");
00269     printf("  t <timeout secs> - total timeout in seconds for anytime search (when plan found)\n");
00270     printf("  T <timeout secs> - total timeout in seconds for anytime search (when no plan found)\n");
00271     printf("  m <monitor file> - monitor plan, validate a given plan\n");
00272     printf("  g - perform greedy search (follow heuristic)\n");
00273     printf("  l - disable lazy evaluation (Lazy = use parent's f instead of child's)\n");
00274     printf("  v - disable verbose printouts\n");
00275     printf("  y - cyclic cg CEA heuristic\n");
00276     printf("  Y - cyclic cg CEA heuristic - preferred operators\n");
00277     printf("  x - cyclic cg makespan heuristic \n");
00278     printf("  X - cyclic cg makespan heuristic - preferred operators\n");
00279     printf("  G [m|c|t|w] - G value evaluation, one of m - makespan, c - pathcost, t - timestamp, w [weight] - weighted / Note: One of those has to be set!\n");
00280     printf("  Q [r|p|h] - queue mode, one of r - round robin, p - priority, h - hierarchical\n");
00281     printf("  K - use tss known filtering (might crop search space)!\n");
00282     printf("  n - no_heuristic\n");
00283     printf("  r - reschedule_plans\n");
00284     printf("  e - epsilonize internally\n");
00285     printf("  f - epsilonize externally\n");
00286     printf("  p <plan file> - plan filename prefix\n");
00287     printf("  M v - monitoring: verify timestamps\n");
00288 }
00289 
00290 bool PlannerParameters::readCmdLineParameters(int argc, char** argv)
00291 {
00292     for (int i = 1; i < argc; i++) {
00293         for (const char *c = argv[i]; *c != 0; c++) {
00294             if (*c == 'a') {
00295                 anytime_search = true;
00296             } else if (*c == 'c') {
00297                 disallow_concurrent_actions = true;
00298             } else if (*c == 't') {
00299                 assert(i + 1 < argc);
00300                 timeout_if_plan_found = atoi(string(argv[++i]).c_str());
00301             } else if (*c == 'T') {
00302                 assert(i + 1 < argc);
00303                 timeout_while_no_plan_found = atoi(string(argv[++i]).c_str());
00304             } else if (*c == 'm') {
00305                 assert(i + 1 < argc);
00306                 planMonitorFileName = string(argv[++i]);
00307             } else if (*c == 'g') {
00308                 greedy = true;
00309             } else if (*c == 'l') {
00310                 lazy_evaluation = false;
00311             } else if (*c == 'v') {
00312                 verbose = false;
00313             } else if (*c == 'y') {
00314                 cyclic_cg_heuristic = true;
00315             } else if (*c == 'Y') {
00316                 cyclic_cg_preferred_operators = true;
00317             } else if (*c == 'x') {
00318                 makespan_heuristic = true;
00319             } else if (*c == 'X') {
00320                 makespan_heuristic_preferred_operators = true;
00321             } else if (*c == 'n') {
00322                 no_heuristic = true;
00323             } else if (*c == 'G') {
00324                 assert(i + 1 < argc);
00325                 const char *g = argv[++i];
00326                 if (*g == 'm') {
00327                     g_values = GMakespan;
00328                 } else if (*g == 'c') {
00329                     g_values = GCost;
00330                 } else if (*g == 't') {
00331                     g_values = GTimestamp;
00332                 } else {
00333                     assert(*g == 'w');
00334                     g_values = GWeighted;
00335                     assert(i + 1 < argc);
00336                     g_weight = strtod(argv[++i], NULL);
00337                     assert(g_weight > 0 && g_weight < 1);  // for 0, 1 use G m or G c, others invalid.
00338                 }
00339             } else if (*c == 'Q') {
00340                 assert(i + 1 < argc);
00341                 const char *g = argv[++i];
00342                 if (*g == 'r') {
00343                     queueManagementMode = BestFirstSearchEngine::ROUND_ROBIN;
00344                 } else {
00345                     assert(*g == 'p');
00346                     queueManagementMode = BestFirstSearchEngine::PRIORITY_BASED;
00347                 }
00348             } else if (*c == 'K') {
00349                 use_known_by_logical_state_only = true;
00350             } else if (*c == 'p') {
00351                 assert(i + 1 < argc);
00352                 plan_name = string(argv[++i]);
00353             } else if (*c == 'r') {
00354                 reschedule_plans = true;
00355             } else if (*c == 'e') {
00356                 epsilonize_internally = true;
00357             } else if (*c == 'f') {
00358                 epsilonize_externally = true;
00359             } else if (*c == 'M') {
00360                 assert(i + 1 < argc);
00361                 const char *g = argv[++i];
00362                 assert(*g == 'v');
00363                 if (*g == 'v') {
00364                     monitoring_verify_timestamps = true;
00365                 }
00366             } else {
00367                 cerr << "Unknown option: " << *c << endl;
00368                 printUsage();
00369                 return false;
00370             }
00371         }
00372     }
00373 
00374     return true;
00375 }
00376 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


tfd_modules
Author(s): Maintained by Christian Dornhege (see AUTHORS file).
autogenerated on Tue Jan 22 2013 12:25:03