41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ 42 #define MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ 48 #include <geometry_msgs/PoseStamped.h> 89 const MoveBaseFlexConfig &config);
99 std::vector<geometry_msgs::PoseStamped>
getPlan()
const;
159 void setNewGoal(
const geometry_msgs::PoseStamped &goal,
double tolerance);
173 void setNewStartAndGoal(
const geometry_msgs::PoseStamped &start,
const geometry_msgs::PoseStamped &goal,
183 bool start(
const geometry_msgs::PoseStamped &start,
const geometry_msgs::PoseStamped &goal,
191 void reconfigure(
const MoveBaseFlexConfig &config);
220 const geometry_msgs::PoseStamped &start,
221 const geometry_msgs::PoseStamped &goal,
223 std::vector<geometry_msgs::PoseStamped> &plan,
225 std::string &message);
262 std::vector<geometry_msgs::PoseStamped>
plan_;
ros::Time last_valid_plan_time_
the last time a valid plan has been computed.
std::vector< geometry_msgs::PoseStamped > getPlan() const
Returns a new plan, if one is available.
std::string plugin_name_
the name of the loaded planner plugin
geometry_msgs::PoseStamped goal_
the current goal pose used for planning
void setState(PlanningState state, bool signalling)
Sets the internal state, thread communication safe.
bool has_new_start_
true, if a new start pose has been set, until it is used.
int max_retries_
planning max retries
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...
geometry_msgs::PoseStamped start_
the current start pose used for planning
The planner has been stopped.
double tolerance_
optional goal tolerance, in meters
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
PlanningState state_
current internal state
PlanningState getState() const
Returns the current internal state.
bool isPatienceExceeded() const
Checks whether the patience was exceeded.
boost::mutex configuration_mutex_
dynamic reconfigure mutex for a thread safe communication
The planner has been canceled.
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...
bool planning_
main cycle variable of the execution loop
double cost_
current global plan cost
Exceeded the maximum number of retries without a valid command.
double getFrequency() const
Gets planning frequency.
ros::Time last_call_start_time_
the last call start time, updated each cycle.
An internal error occurred.
boost::mutex state_mtx_
mutex to handle safe thread communication for the current state
void setNewStart(const geometry_msgs::PoseStamped &start)
Sets a new start pose for the planner execution.
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
Exceeded the patience time without a valid command.
void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance)
Sets a new goal pose for the planner execution.
double frequency_
planning cycle frequency (used only when running full navigation; we store here for grouping paramete...
boost::mutex plan_mtx_
mutex to handle safe thread communication for the plan and plan-costs
PlanningState
Internal states.
std::string global_frame_
the global frame in which the planner needs to plan
boost::mutex goal_start_mtx_
mutex to handle safe thread communication for the goal and start pose.
std::vector< geometry_msgs::PoseStamped > plan_
current global plan
double getCost() const
Gets computed costs.
AbstractPlannerExecution(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config)
Constructor.
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.
bool has_new_goal_
true, if a new goal pose has been set, until it is used.
mbf_abstract_core::AbstractPlanner::Ptr planner_
the local planer to calculate the robot trajectory
boost::mutex planning_mtx_
mutex to handle safe thread communication for the planning_ flag.
virtual ~AbstractPlannerExecution()
Destructor.
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
std::string robot_frame_
robot frame used for computing the current robot pose
const TFPtr tf_listener_ptr_
shared pointer to a common TransformListener
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
ros::Duration patience_
planning patience duration time
ros::Time getLastValidPlanTime() const
Returns the last time a valid plan was available.