navstack_module.h
Go to the documentation of this file.
00001 #ifndef NAVSTACK_MODULE_H
00002 #define NAVSTACK_MODULE_H
00003 
00004 #include "tfd_modules/module_api/pddlModuleTypes.h"
00005 #include "planner_modules_pr2/module_param_cache.h"
00006 #include <map>
00007 #include <string>
00008 #include <utility>
00009 #include <ros/ros.h>
00010 #include <nav_msgs/GetPlan.h>
00011 
00019 static const bool g_Debug = false;
00020 
00021 extern ros::NodeHandle* g_NodeHandle;
00022 extern ros::ServiceClient g_GetPlan;
00023 
00025 extern std::string g_WorldFrame;
00026 
00027 extern double g_GoalTolerance;
00028 
00030 extern double g_TransSpeed; // m/s
00031 extern double g_RotSpeed;   // rad/s
00032 
00033 // Using a cache of queried path costs to prevent calling the path planning service multiple times
00034 // Better: Can we assume symmetric path costs?
00035 //extern std::map< std::pair<std::string, std::string>, double> g_PathCostCache;
00036 extern ModuleParamCacheDouble g_PathCostCache;
00037 string computePathCacheKey(const string& startLocation, const string& goalLocation,
00038         const geometry_msgs::Pose & startPose, const geometry_msgs::Pose & goalPose);
00039 
00040 bool fillPathRequest(const modules::ParameterList & parameterList, modules::numericalFluentCallbackType numericalFluentCallback,
00041         nav_msgs::GetPlan::Request& request);
00042 
00044 
00048 double callPlanningService(nav_msgs::GetPlan& srv, const string& startLocationName, const string& goalLocationName,
00049         bool & callFailure);
00050 
00051 double getPlanCost(const std::vector<geometry_msgs::PoseStamped> & plan);
00052 
00053 #ifdef __cplusplus
00054 extern "C" {
00055 #endif
00056 
00057 void navstack_init(int argc, char** argv);
00058 
00059 double pathCost(const modules::ParameterList & parameterList, modules::predicateCallbackType predicateCallback, 
00060         modules::numericalFluentCallbackType numericalFluentCallback, int relaxed);
00061 
00062 #ifdef __cplusplus
00063 }
00064 #endif
00065 
00066 #endif
00067 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


planner_modules_pr2
Author(s): Christian Dornhege, Andreas Hertle
autogenerated on Wed Dec 26 2012 15:49:38