Go to the documentation of this file.
41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
48 #include <geometry_msgs/PoseStamped.h>
88 const MoveBaseFlexConfig& config);
98 const TFPtr& tf_listener_ptr,
const MoveBaseFlexConfig& config);
108 std::vector<geometry_msgs::PoseStamped>
getPlan()
const;
168 void setNewGoal(
const geometry_msgs::PoseStamped &goal,
double tolerance);
192 bool start(
const geometry_msgs::PoseStamped &
start,
const geometry_msgs::PoseStamped &goal,
200 void reconfigure(
const MoveBaseFlexConfig &config);
232 const geometry_msgs::PoseStamped &
start,
233 const geometry_msgs::PoseStamped &goal,
235 std::vector<geometry_msgs::PoseStamped> &plan,
237 std::string &message);
274 std::vector<geometry_msgs::PoseStamped>
plan_;
@ INTERNAL_ERROR
An internal error occurred.
PlanningState state_
current internal state
boost::mutex planning_mtx_
mutex to handle safe thread communication for the planning_ flag.
geometry_msgs::PoseStamped start_
the current start pose used for planning
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...
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
bool isPatienceExceeded() const
Checks whether the patience was exceeded.
@ PLANNING
Executing the plugin.
double tolerance_
optional goal tolerance, in meters
ros::Time getLastValidPlanTime() const
Returns the last time a valid plan was available.
const TFPtr tf_listener_ptr_
shared pointer to a common TransformListener
ros::Duration patience_
planning patience duration time
bool has_new_start_
true, if a new start pose has been set, until it is used.
ros::Time last_call_start_time_
the last call start time, updated each cycle.
boost::shared_ptr< AbstractPlannerExecution > Ptr
shared pointer type to the planner execution.
virtual void run()
The main run method, a thread will execute this method. It contains the main planner execution loop.
std::string plugin_name_
the name of the loaded planner plugin
void setNewStart(const geometry_msgs::PoseStamped &start)
Sets a new start pose for the planner execution.
@ PAT_EXCEEDED
Exceeded the patience time without a valid command.
double frequency_
planning cycle frequency (used only when running full navigation; we store here for grouping paramete...
double getCost() const
Gets computed costs.
@ NO_PLAN_FOUND
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
@ INITIALIZED
Planner initialized.
double cost_
current global plan cost
bool planning_
main cycle variable of the execution loop
double getFrequency() const
Gets planning frequency.
std::vector< geometry_msgs::PoseStamped > getPlan() const
Returns a new plan, if one is available.
boost::mutex state_mtx_
mutex to handle safe thread communication for the current state
std::string robot_frame_
robot frame used for computing the current robot pose
AbstractPlannerExecution(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config)
Constructor.
@ STOPPED
The planner has been stopped.
@ MAX_RETRIES
Exceeded the maximum number of retries without a valid command.
@ CANCELED
The planner has been canceled.
std::vector< geometry_msgs::PoseStamped > plan_
current global plan
PlanningState getState() const
Returns the current internal state.
virtual ~AbstractPlannerExecution()
Destructor.
std::string global_frame_
the global frame in which the planner needs to plan
boost::mutex plan_mtx_
mutex to handle safe thread communication for the plan and plan-costs
boost::mutex goal_start_mtx_
mutex to handle safe thread communication for the goal and start pose.
bool has_new_goal_
true, if a new goal pose has been set, until it is used.
void setState(PlanningState state, bool signalling)
Sets the internal state, thread communication safe.
ros::Time last_valid_plan_time_
the last time a valid plan has been computed.
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
Base class for running concurrent navigation tasks.
void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance)
Sets a new goal pose for the planner execution.
PlanningState
Internal states.
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
@ FOUND_PLAN
Found a valid plan.
int max_retries_
planning max retries
@ STARTED
Planner started.
mbf_abstract_core::AbstractPlanner::Ptr planner_
the local planer to calculate the robot trajectory
geometry_msgs::PoseStamped goal_
the current goal pose used for planning
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.
boost::mutex configuration_mutex_
dynamic reconfigure mutex for a thread safe communication
mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47