The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread running the plugin in a cycle to plan and re-plan. An internal state is saved and will be pulled by the server, which controls the global planner execution. Due to a state change it wakes up all threads connected to the condition variable. More...
#include <abstract_planner_execution.h>
Public Types | |
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... | |
Public Member Functions | |
AbstractPlannerExecution (const std::string name, const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn) | |
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. More... | |
double | getCost () |
Gets computed costs. More... | |
double | getFrequency () |
Gets planning frequency. More... | |
ros::Time | getLastValidPlanTime () |
Returns the last time a valid plan was available. More... | |
std::vector< geometry_msgs::PoseStamped > | getPlan () |
Returns a new plan, if one is available. More... | |
PlanningState | getState () |
Returns the current internal state. More... | |
bool | isPatienceExceeded () |
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 (std::string name, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn) | |
std::string | getMessage () |
Gets the current plugin execution message. More... | |
std::string | getName () |
Returns the name of the corresponding plugin. More... | |
uint32_t | getOutcome () |
Gets the current plugin execution outcome. More... | |
void | join () |
virtual bool | start () |
virtual void | stop () |
void | waitForStateUpdate (boost::chrono::microseconds const &duration) |
Protected Member Functions | |
virtual void | run () |
The main run method, a thread will execute this method. It contains the main planner execution loop. More... | |
Protected Attributes | |
mbf_abstract_core::AbstractPlanner::Ptr | planner_ |
the local planer to calculate the velocity command More... | |
std::string | plugin_name_ |
the name of the loaded planner plugin 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... | |
Private Member Functions | |
virtual uint32_t | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message) |
calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance, if a goal tolerance is enabled in the planner plugin. More... | |
void | setState (PlanningState state) |
Sets the internal state, thread communication safe. More... | |
Private Attributes | |
boost::mutex | configuration_mutex_ |
dynamic reconfigure mutex for a thread safe communication More... | |
double | cost_ |
current global plan cost More... | |
double | frequency_ |
planning cycle frequency (used only when running full navigation; we store here for grouping parameters nicely) More... | |
std::string | global_frame_ |
the global frame in which the planner needs to plan More... | |
geometry_msgs::PoseStamped | goal_ |
the current goal pose used for planning More... | |
boost::mutex | goal_start_mtx_ |
mutex to handle safe thread communication for the goal and start pose. More... | |
bool | has_new_goal_ |
true, if a new goal pose has been set, until it is used. More... | |
bool | has_new_start_ |
true, if a new start pose has been set, until it is used. More... | |
ros::Time | last_call_start_time_ |
the last call start time, updated each cycle. More... | |
ros::Time | last_valid_plan_time_ |
the last time a valid plan has been computed. More... | |
int | max_retries_ |
planning max retries More... | |
ros::Duration | patience_ |
planning patience duration time More... | |
std::vector< geometry_msgs::PoseStamped > | plan_ |
current global plan More... | |
boost::mutex | plan_mtx_ |
mutex to handle safe thread communication for the plan and plan-costs More... | |
bool | planning_ |
main cycle variable of the execution loop More... | |
boost::mutex | planning_mtx_ |
mutex to handle safe thread communication for the planning_ flag. More... | |
std::string | robot_frame_ |
robot frame used for computing the current robot pose More... | |
geometry_msgs::PoseStamped | start_ |
the current start pose used for planning More... | |
PlanningState | state_ |
current internal state More... | |
boost::mutex | state_mtx_ |
mutex to handle safe thread communication for the current state More... | |
const TFPtr | tf_listener_ptr_ |
shared pointer to a common TransformListener More... | |
double | tolerance_ |
optional goal tolerance, in meters More... | |
Additional Inherited Members | |
Public Attributes inherited from mbf_abstract_nav::AbstractExecutionBase | |
boost::function< void()> | cleanup_fn_ |
Implementation-specific cleanup function called right after execution; empty on abstract server. More... | |
boost::function< void()> | setup_fn_ |
Implementation-specific setup function called right before execution; empty on abstract server. More... | |
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread running the plugin in a cycle to plan and re-plan. An internal state is saved and will be pulled by the server, which controls the global planner execution. Due to a state change it wakes up all threads connected to the condition variable.
Definition at line 76 of file abstract_planner_execution.h.
typedef boost::shared_ptr<AbstractPlannerExecution > mbf_abstract_nav::AbstractPlannerExecution::Ptr |
shared pointer type to the planner execution.
Definition at line 81 of file abstract_planner_execution.h.
Internal states.
Definition at line 120 of file abstract_planner_execution.h.
mbf_abstract_nav::AbstractPlannerExecution::AbstractPlannerExecution | ( | const std::string | name, |
const mbf_abstract_core::AbstractPlanner::Ptr | planner_ptr, | ||
const MoveBaseFlexConfig & | config, | ||
boost::function< void()> | setup_fn, | ||
boost::function< void()> | cleanup_fn | ||
) |
Constructor.
condition | Thread sleep condition variable, to wake up connected threads |
Definition at line 47 of file abstract_planner_execution.cpp.
|
virtual |
Destructor.
Definition at line 66 of file abstract_planner_execution.cpp.
|
virtual |
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be useful if the computation takes too much time.
Implements mbf_abstract_nav::AbstractExecutionBase.
Definition at line 193 of file abstract_planner_execution.cpp.
double mbf_abstract_nav::AbstractPlannerExecution::getCost | ( | ) |
Gets computed costs.
Definition at line 71 of file abstract_planner_execution.cpp.
|
inline |
Gets planning frequency.
Definition at line 143 of file abstract_planner_execution.h.
ros::Time mbf_abstract_nav::AbstractPlannerExecution::getLastValidPlanTime | ( | ) |
Returns the last time a valid plan was available.
Definition at line 118 of file abstract_planner_execution.cpp.
std::vector< geometry_msgs::PoseStamped > mbf_abstract_nav::AbstractPlannerExecution::getPlan | ( | ) |
Returns a new plan, if one is available.
plan | A reference to a plan, which then will be filled. |
cost | A reference to the costs, which then will be filled. |
Definition at line 131 of file abstract_planner_execution.cpp.
AbstractPlannerExecution::PlanningState mbf_abstract_nav::AbstractPlannerExecution::getState | ( | ) |
Returns the current internal state.
Definition at line 105 of file abstract_planner_execution.cpp.
bool mbf_abstract_nav::AbstractPlannerExecution::isPatienceExceeded | ( | ) |
Checks whether the patience was exceeded.
Definition at line 125 of file abstract_planner_execution.cpp.
|
privatevirtual |
calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance, if a goal tolerance is enabled in the planner plugin.
start | The start pose for planning |
goal | The goal pose for planning |
tolerance | The goal tolerance |
plan | The computed plan by the plugin |
cost | The computed costs for the corresponding plan |
message | An optional message which should correspond with the returned outcome |
Definition at line 208 of file abstract_planner_execution.cpp.
void mbf_abstract_nav::AbstractPlannerExecution::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.
config | MoveBaseFlexConfig object |
Definition at line 92 of file abstract_planner_execution.cpp.
|
protectedvirtual |
The main run method, a thread will execute this method. It contains the main planner execution loop.
Implements mbf_abstract_nav::AbstractExecutionBase.
Definition at line 218 of file abstract_planner_execution.cpp.
void mbf_abstract_nav::AbstractPlannerExecution::setNewGoal | ( | const geometry_msgs::PoseStamped & | goal, |
double | tolerance | ||
) |
Sets a new goal pose for the planner execution.
goal | the new goal pose |
tolerance | tolerance to the goal for the planning |
Definition at line 139 of file abstract_planner_execution.cpp.
void mbf_abstract_nav::AbstractPlannerExecution::setNewStart | ( | const geometry_msgs::PoseStamped & | start | ) |
Sets a new start pose for the planner execution.
start | new start pose |
Definition at line 148 of file abstract_planner_execution.cpp.
void mbf_abstract_nav::AbstractPlannerExecution::setNewStartAndGoal | ( | const geometry_msgs::PoseStamped & | start, |
const geometry_msgs::PoseStamped & | goal, | ||
double | tolerance | ||
) |
Sets a new star and goal pose for the planner execution.
start | new start pose |
goal | new goal pose |
tolerance | tolerance to the new goal for the planning |
Definition at line 156 of file abstract_planner_execution.cpp.
|
private |
Sets the internal state, thread communication safe.
state | the current state |
Definition at line 111 of file abstract_planner_execution.cpp.
bool mbf_abstract_nav::AbstractPlannerExecution::start | ( | const geometry_msgs::PoseStamped & | start, |
const geometry_msgs::PoseStamped & | goal, | ||
double | tolerance | ||
) |
Starts the planner execution thread with the given parameters.
start | start pose for the planning |
goal | goal pose for the planning |
tolerance | tolerance to the goal pose for the planning |
Definition at line 169 of file abstract_planner_execution.cpp.
|
private |
dynamic reconfigure mutex for a thread safe communication
Definition at line 301 of file abstract_planner_execution.h.
|
private |
current global plan cost
Definition at line 265 of file abstract_planner_execution.h.
|
private |
planning cycle frequency (used only when running full navigation; we store here for grouping parameters nicely)
Definition at line 277 of file abstract_planner_execution.h.
|
private |
the global frame in which the planner needs to plan
Definition at line 292 of file abstract_planner_execution.h.
|
private |
the current goal pose used for planning
Definition at line 271 of file abstract_planner_execution.h.
|
private |
mutex to handle safe thread communication for the goal and start pose.
Definition at line 244 of file abstract_planner_execution.h.
|
private |
true, if a new goal pose has been set, until it is used.
Definition at line 250 of file abstract_planner_execution.h.
|
private |
true, if a new start pose has been set, until it is used.
Definition at line 253 of file abstract_planner_execution.h.
|
private |
the last call start time, updated each cycle.
Definition at line 256 of file abstract_planner_execution.h.
|
private |
the last time a valid plan has been computed.
Definition at line 259 of file abstract_planner_execution.h.
|
private |
planning max retries
Definition at line 283 of file abstract_planner_execution.h.
|
private |
planning patience duration time
Definition at line 280 of file abstract_planner_execution.h.
|
private |
current global plan
Definition at line 262 of file abstract_planner_execution.h.
|
private |
mutex to handle safe thread communication for the plan and plan-costs
Definition at line 241 of file abstract_planner_execution.h.
|
protected |
the local planer to calculate the velocity command
Definition at line 200 of file abstract_planner_execution.h.
|
private |
main cycle variable of the execution loop
Definition at line 286 of file abstract_planner_execution.h.
|
private |
mutex to handle safe thread communication for the planning_ flag.
Definition at line 247 of file abstract_planner_execution.h.
|
protected |
the name of the loaded planner plugin
Definition at line 203 of file abstract_planner_execution.h.
|
private |
robot frame used for computing the current robot pose
Definition at line 289 of file abstract_planner_execution.h.
|
private |
the current start pose used for planning
Definition at line 268 of file abstract_planner_execution.h.
|
private |
current internal state
Definition at line 298 of file abstract_planner_execution.h.
|
private |
mutex to handle safe thread communication for the current state
Definition at line 238 of file abstract_planner_execution.h.
|
private |
shared pointer to a common TransformListener
Definition at line 295 of file abstract_planner_execution.h.
|
private |
optional goal tolerance, in meters
Definition at line 274 of file abstract_planner_execution.h.