Go to the documentation of this file.
47 const MoveBaseFlexConfig& config)
49 , planner_(planner_ptr)
53 , has_new_start_(false)
54 , has_new_goal_(false)
68 const TFPtr& tf_listener_ptr,
const MoveBaseFlexConfig& config)
70 , planner_(planner_ptr)
74 , tf_listener_ptr_(tf_listener_ptr)
75 , has_new_start_(false)
76 , has_new_goal_(false)
92 template <
typename _Iter>
100 if (std::distance(_begin, _end) < 2)
104 for (_Iter next = _begin + 1; next != _end; ++_begin, ++next)
128 catch (std::exception& ex)
138 boost::lock_guard<boost::mutex> guard(
state_mtx_);
144 boost::lock_guard<boost::mutex> guard(
state_mtx_);
158 boost::lock_guard<boost::mutex> guard(
plan_mtx_);
171 boost::lock_guard<boost::mutex> guard(
plan_mtx_);
195 const geometry_msgs::PoseStamped &goal,
208 const geometry_msgs::PoseStamped &goal,
221 const geometry_msgs::Point&
s =
start.pose.position;
222 const geometry_msgs::Point& g = goal.pose.position;
224 ROS_DEBUG_STREAM(
"Start planning from the start pose: (" <<
s.x <<
", " <<
s.y <<
", " <<
s.z <<
")"
225 <<
" to the goal pose: ("<< g.x <<
", " << g.y <<
", " << g.z <<
")");
238 ROS_WARN_STREAM(
"Cancel planning failed or is not supported by the plugin. "
239 <<
"Wait until the current planning finished!");
247 const geometry_msgs::PoseStamped &goal,
249 std::vector<geometry_msgs::PoseStamped> &plan,
251 std::string &message)
253 return planner_->makePlan(
start, goal, tolerance, plan, cost, message);
261 geometry_msgs::PoseStamped current_start =
start_;
262 geometry_msgs::PoseStamped current_goal =
goal_;
273 std::vector<geometry_msgs::PoseStamped> plan;
282 ROS_INFO_STREAM(
"A new start pose is available. Planning with the new start pose!");
283 const geometry_msgs::Point&
s =
start_.pose.position;
284 ROS_INFO_STREAM(
"New planning start pose: (" <<
s.x <<
", " <<
s.y <<
", " <<
s.z <<
")");
289 current_goal =
goal_;
291 ROS_INFO_STREAM(
"A new goal pose is available. Planning with the new goal pose and the tolerance: "
292 << current_tolerance);
293 const geometry_msgs::Point& g =
goal_.pose.position;
294 ROS_INFO_STREAM(
"New goal pose: (" << g.x <<
", " << g.y <<
", " << g.z <<
")");
322 boost::lock_guard<boost::mutex> plan_mtx_guard(
plan_mtx_);
344 << (
cancel_ ?
"; planner canceled!" :
""));
359 catch (
const boost::thread_interrupted &ex)
367 ROS_ERROR_STREAM(
"Unknown error occurred: " << boost::current_exception_diagnostic_information());
@ 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...
#define ROS_ERROR_STREAM(args)
bool cancel_
flag for canceling controlling
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
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.
uint32_t outcome_
the last received plugin execution outcome
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.
virtual void run()
The main run method, a thread will execute this method. It contains the main planner execution loop.
#define ROS_DEBUG_STREAM(args)
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...
#define ROS_WARN_STREAM(args)
double getCost() const
Gets computed costs.
boost::condition_variable condition_
condition variable to wake up control thread
@ NO_PLAN_FOUND
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
double cost_
current global plan cost
bool planning_
main cycle variable of the execution loop
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
#define ROS_INFO_STREAM(args)
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
double sumDistance(_Iter _begin, _Iter _end)
PlanningState getState() const
Returns the current internal state.
std::string message_
the last received plugin execution message
virtual ~AbstractPlannerExecution()
Destructor.
std::string global_frame_
the global frame in which the planner needs to plan
T param(const std::string ¶m_name, const T &default_val) const
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.
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.
std::string name_
the plugin name; not the plugin type!
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