#include "planner_modules_pr2/navstack_module.h"
#include <ros/ros.h>
#include <nav_msgs/GetPlan.h>
#include <geometry_msgs/PoseStamped.h>
#include <angles/angles.h>
#include <map>
#include <utility>
#include <boost/foreach.hpp>
#include <sys/times.h>
#include <tf/tf.h>
#include <tf/transform_listener.h>
Go to the source code of this file.
Defines | |
#define | forEach BOOST_FOREACH |
Functions | |
double | callPlanningService (nav_msgs::GetPlan &srv, const string &startLocationName, const string &goalLocationName, bool &callSuccessful) |
Return the cost of the plan. | |
string | computePathCacheKey (const string &startLocation, const string &goalLocation, const geometry_msgs::Pose &startPose, const geometry_msgs::Pose &goalPose) |
bool | fillPathRequest (const ParameterList ¶meterList, numericalFluentCallbackType numericalFluentCallback, nav_msgs::GetPlan::Request &request) |
double | getPlanCost (const std::vector< geometry_msgs::PoseStamped > &plan) |
void | navstack_init (int argc, char **argv) |
double | pathCost (const ParameterList ¶meterList, predicateCallbackType predicateCallback, numericalFluentCallbackType numericalFluentCallback, int relaxed) |
VERIFY_CONDITIONCHECKER_DEF (pathCost) | |
Variables | |
ros::ServiceClient | g_GetPlan |
double | g_GoalTolerance = 0.5 |
ros::NodeHandle * | g_NodeHandle = NULL |
ModuleParamCacheDouble | g_PathCostCache |
double | g_RotSpeed = angles::from_degrees(30) |
double | g_TransSpeed = 0.3 |
speed values for computing the estimated time as cost of a path | |
std::string | g_WorldFrame |
Plan requests are issued using this frame - so the poses from the planner are given in this frame (e.g. map) |
#define forEach BOOST_FOREACH |
Definition at line 14 of file navstack_module.cpp.
double callPlanningService | ( | nav_msgs::GetPlan & | srv, |
const string & | startLocationName, | ||
const string & | goalLocationName, | ||
bool & | callFailure | ||
) |
Return the cost of the plan.
[out] | callFailure | is set to true, if there was some failure during the call, i.e. the resulting INFINITE_COST does not represent necessarily the impossibility of a path. |
Definition at line 222 of file navstack_module.cpp.
string computePathCacheKey | ( | const string & | startLocation, |
const string & | goalLocation, | ||
const geometry_msgs::Pose & | startPose, | ||
const geometry_msgs::Pose & | goalPose | ||
) |
Definition at line 40 of file navstack_module.cpp.
bool fillPathRequest | ( | const ParameterList & | parameterList, |
numericalFluentCallbackType | numericalFluentCallback, | ||
nav_msgs::GetPlan::Request & | request | ||
) |
Definition at line 145 of file navstack_module.cpp.
double getPlanCost | ( | const std::vector< geometry_msgs::PoseStamped > & | plan | ) |
Definition at line 199 of file navstack_module.cpp.
void navstack_init | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 56 of file navstack_module.cpp.
double pathCost | ( | const ParameterList & | parameterList, |
predicateCallbackType | predicateCallback, | ||
numericalFluentCallbackType | numericalFluentCallback, | ||
int | relaxed | ||
) |
Definition at line 285 of file navstack_module.cpp.
Definition at line 26 of file navstack_module.cpp.
double g_GoalTolerance = 0.5 |
Definition at line 31 of file navstack_module.cpp.
Definition at line 25 of file navstack_module.cpp.
Definition at line 39 of file navstack_module.cpp.
double g_RotSpeed = angles::from_degrees(30) |
Definition at line 34 of file navstack_module.cpp.
double g_TransSpeed = 0.3 |
speed values for computing the estimated time as cost of a path
Definition at line 33 of file navstack_module.cpp.
std::string g_WorldFrame |
Plan requests are issued using this frame - so the poses from the planner are given in this frame (e.g. map)
Definition at line 29 of file navstack_module.cpp.