
| Public Member Functions | |
| AbstractPlannerExecutionFixture () | |
| void | TearDown () override | 
|  Public Member Functions inherited from mbf_abstract_nav::AbstractPlannerExecution | |
| AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config) | |
| Constructor.  More... | |
| AbstractPlannerExecution (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const TFPtr &tf_listener_ptr, const MoveBaseFlexConfig &config) | |
| Constructor.  More... | |
| virtual bool | cancel () | 
| Cancel the planner execution. This calls the cancel method of the planner plugin. This could be useful if the computation takes too much time, or if we are aborting the navigation.  More... | |
| double | getCost () const | 
| Gets computed costs.  More... | |
| double | getFrequency () const | 
| Gets planning frequency.  More... | |
| ros::Time | getLastValidPlanTime () const | 
| Returns the last time a valid plan was available.  More... | |
| std::vector< geometry_msgs::PoseStamped > | getPlan () const | 
| Returns a new plan, if one is available.  More... | |
| PlanningState | getState () const | 
| Returns the current internal state.  More... | |
| bool | isPatienceExceeded () const | 
| Checks whether the patience was exceeded.  More... | |
| void | reconfigure (const MoveBaseFlexConfig &config) | 
| Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconfigure to reconfigure the current state.  More... | |
| void | setNewGoal (const geometry_msgs::PoseStamped &goal, double tolerance) | 
| Sets a new goal pose for the planner execution.  More... | |
| void | setNewStart (const geometry_msgs::PoseStamped &start) | 
| Sets a new start pose for the planner execution.  More... | |
| void | setNewStartAndGoal (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance) | 
| Sets a new star and goal pose for the planner execution.  More... | |
| bool | start (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance) | 
| Starts the planner execution thread with the given parameters.  More... | |
| virtual | ~AbstractPlannerExecution () | 
| Destructor.  More... | |
|  Public Member Functions inherited from mbf_abstract_nav::AbstractExecutionBase | |
| AbstractExecutionBase (const std::string &name) | |
| const std::string & | getMessage () const | 
| Gets the current plugin execution message.  More... | |
| const std::string & | getName () const | 
| Returns the name of the corresponding plugin.  More... | |
| uint32_t | getOutcome () const | 
| Gets the current plugin execution outcome.  More... | |
| void | join () | 
| virtual void | postRun () | 
| Optional implementation-specific cleanup function, called right after execution.  More... | |
| virtual void | preRun () | 
| Optional implementation-specific setup function, called right before execution.  More... | |
| virtual void | reconfigure (MoveBaseFlexConfig &_cfg) | 
| Optional implementaiton-specific configuration function.  More... | |
| virtual bool | start () | 
| virtual void | stop () | 
| boost::cv_status | waitForStateUpdate (boost::chrono::microseconds const &duration) | 
| virtual | ~AbstractExecutionBase () | 
| Public Attributes | |
| PoseStamped | pose | 
| Additional Inherited Members | |
|  Public Types inherited from mbf_abstract_nav::AbstractPlannerExecution | |
| enum | PlanningState { INITIALIZED, STARTED, PLANNING, FOUND_PLAN, MAX_RETRIES, PAT_EXCEEDED, NO_PLAN_FOUND, CANCELED, STOPPED, INTERNAL_ERROR } | 
| Internal states.  More... | |
| typedef boost::shared_ptr< AbstractPlannerExecution > | Ptr | 
| shared pointer type to the planner execution.  More... | |
|  Protected Member Functions inherited from mbf_abstract_nav::AbstractPlannerExecution | |
| virtual void | run () | 
| The main run method, a thread will execute this method. It contains the main planner execution loop.  More... | |
|  Protected Attributes inherited from mbf_abstract_nav::AbstractPlannerExecution | |
| mbf_abstract_core::AbstractPlanner::Ptr | planner_ | 
| the local planer to calculate the robot trajectory  More... | |
| std::string | plugin_name_ | 
| the name of the loaded planner plugin  More... | |
| const TFPtr | tf_listener_ptr_ | 
| shared pointer to a common TransformListener  More... | |
|  Protected Attributes inherited from mbf_abstract_nav::AbstractExecutionBase | |
| bool | cancel_ | 
| flag for canceling controlling  More... | |
| boost::condition_variable | condition_ | 
| condition variable to wake up control thread  More... | |
| std::string | message_ | 
| the last received plugin execution message  More... | |
| std::string | name_ | 
| the plugin name; not the plugin type!  More... | |
| uint32_t | outcome_ | 
| the last received plugin execution outcome  More... | |
| boost::thread | thread_ | 
| the controlling thread object  More... | |
Definition at line 29 of file test/abstract_planner_execution.cpp.
| 
 | inline | 
Definition at line 33 of file test/abstract_planner_execution.cpp.
| 
 | inlineoverride | 
Definition at line 38 of file test/abstract_planner_execution.cpp.
| PoseStamped AbstractPlannerExecutionFixture::pose | 
Definition at line 31 of file test/abstract_planner_execution.cpp.