src/abstract_controller_execution.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * abstract_controller_execution.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #include <mbf_msgs/ExePathResult.h>
42 
44 
45 namespace mbf_abstract_nav
46 {
47 
49 
51  const std::string &name,
52  const mbf_abstract_core::AbstractController::Ptr &controller_ptr,
53  const ros::Publisher &vel_pub,
54  const ros::Publisher &goal_pub,
55  const TFPtr &tf_listener_ptr,
56  const MoveBaseFlexConfig &config) :
58  controller_(controller_ptr), tf_listener_ptr(tf_listener_ptr), state_(INITIALIZED),
59  moving_(false), max_retries_(0), patience_(0), vel_pub_(vel_pub), current_goal_pub_(goal_pub),
60  loop_rate_(DEFAULT_CONTROLLER_FREQUENCY)
61 {
62  ros::NodeHandle nh;
63  ros::NodeHandle private_nh("~");
64 
65  // non-dynamically reconfigurable parameters
66  private_nh.param("robot_frame", robot_frame_, std::string("base_link"));
67  private_nh.param("map_frame", global_frame_, std::string("map"));
68  private_nh.param("force_stop_at_goal", force_stop_at_goal_, false);
69  private_nh.param("force_stop_on_cancel", force_stop_on_cancel_, false);
70  private_nh.param("mbf_tolerance_check", mbf_tolerance_check_, false);
71  private_nh.param("dist_tolerance", dist_tolerance_, 0.1);
72  private_nh.param("angle_tolerance", angle_tolerance_, M_PI / 18.0);
73  private_nh.param("tf_timeout", tf_timeout_, 1.0);
74 
75  // dynamically reconfigurable parameters
76  reconfigure(config);
77 }
78 
80 {
81 }
82 
84 {
85  // set the calling duration by the moving frequency
86  if (frequency <= 0.0)
87  {
88  ROS_ERROR("Controller frequency must be greater than 0.0! No change of the frequency!");
89  return false;
90  }
91  loop_rate_ = ros::Rate(frequency);
92  return true;
93 }
94 
95 void AbstractControllerExecution::reconfigure(const MoveBaseFlexConfig &config)
96 {
97  boost::lock_guard<boost::mutex> guard(configuration_mutex_);
98  // Timeout granted to the controller. We keep calling it up to this time or up to max_retries times
99  // If it doesn't return within time, the navigator will cancel it and abort the corresponding action
100  patience_ = ros::Duration(config.controller_patience);
101 
102  setControllerFrequency(config.controller_frequency);
103 
104  max_retries_ = config.controller_max_retries;
105 }
106 
107 
109 {
110  setState(STARTED);
111  if (moving_)
112  {
113  return false; // thread is already running.
114  }
115  moving_ = true;
117 }
118 
119 
121 {
122  boost::lock_guard<boost::mutex> guard(state_mtx_);
123  state_ = state;
124 }
125 
127 {
128  boost::lock_guard<boost::mutex> guard(state_mtx_);
129  return state_;
130 }
131 
133  const std::vector<geometry_msgs::PoseStamped> &plan,
134  bool tolerance_from_action,
135  double action_dist_tolerance,
136  double action_angle_tolerance)
137 {
138  if (moving_)
139  {
140  // This is fine on continuous replanning
141  ROS_DEBUG("Setting new plan while moving");
142  }
143  boost::lock_guard<boost::mutex> guard(plan_mtx_);
144  new_plan_ = true;
145 
146  plan_ = plan;
147  tolerance_from_action_ = tolerance_from_action;
148  action_dist_tolerance_ = action_dist_tolerance;
149  action_angle_tolerance_ = action_angle_tolerance;
150 }
151 
152 
154 {
155  boost::lock_guard<boost::mutex> guard(plan_mtx_);
156  return new_plan_;
157 }
158 
159 
160 std::vector<geometry_msgs::PoseStamped> AbstractControllerExecution::getNewPlan()
161 {
162  boost::lock_guard<boost::mutex> guard(plan_mtx_);
163  new_plan_ = false;
164  return plan_;
165 }
166 
167 
169 {
172  {
173  ROS_ERROR_STREAM("Could not get the robot pose in the global frame. - robot frame: \""
174  << robot_frame_ << "\" global frame: \"" << global_frame_);
175  message_ = "Could not get the robot pose";
176  outcome_ = mbf_msgs::ExePathResult::TF_ERROR;
177  return false;
178  }
179  return true;
180 }
181 
182 
183 uint32_t AbstractControllerExecution::computeVelocityCmd(const geometry_msgs::PoseStamped &robot_pose,
184  const geometry_msgs::TwistStamped &robot_velocity,
185  geometry_msgs::TwistStamped &vel_cmd,
186  std::string &message)
187 {
188  return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
189 }
190 
191 
192 void AbstractControllerExecution::setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd)
193 {
194  boost::lock_guard<boost::mutex> guard(vel_cmd_mtx_);
195  vel_cmd_stamped_ = vel_cmd;
196  if (vel_cmd_stamped_.header.stamp.isZero())
197  vel_cmd_stamped_.header.stamp = ros::Time::now();
198  // TODO what happen with frame id?
199  // TODO Add a queue here for handling the outcome, message and cmd_vel values bundled,
200  // TODO so there should be no loss of information in the feedback stream
201 }
202 
203 geometry_msgs::TwistStamped AbstractControllerExecution::getVelocityCmd() const
204 {
205  boost::lock_guard<boost::mutex> guard(vel_cmd_mtx_);
206  return vel_cmd_stamped_;
207 }
208 
210 {
211  boost::lock_guard<boost::mutex> guard(lct_mtx_);
212  return last_call_time_;
213 }
214 
216 {
217  boost::lock_guard<boost::mutex> guard(lct_mtx_);
218  if(!patience_.isZero() && ros::Time::now() - start_time_ > patience_) // not zero -> activated, start_time handles init case
219  {
221  {
222  ROS_WARN_STREAM_THROTTLE(3, "The controller plugin \"" << name_ << "\" needs more time to compute in one run than the patience time!");
223  return true;
224  }
226  {
227  ROS_DEBUG_STREAM("The controller plugin \"" << name_ << "\" does not return a success state (outcome < 10) for more than the patience time in multiple runs!");
228  return true;
229  }
230  }
231  return false;
232 }
233 
235 {
236  return moving_;
237 }
238 
240 {
241  //if action has a specific tolerance, check goal reached with those tolerances
243  {
247  }
248 
249  // Otherwise, check whether the controller plugin returns goal reached or if mbf should check for goal reached.
253 }
254 
256 {
257  // Request the controller to cancel; it will return true if it takes care of stopping, returning CANCELED on
258  // computeVelocityCmd when done. This allows for smooth, controlled stops.
259  // If false (meaning cancel is not implemented, or that the controller defers handling it) MBF will take care.
260  if (controller_->cancel())
261  {
262  ROS_INFO("Controller will take care of stopping");
263  }
264  else
265  {
266  ROS_WARN("Controller defers handling cancel; force it and wait until the current control cycle finished");
267  cancel_ = true;
268  // wait for the control cycle to stop
269  if (waitForStateUpdate(boost::chrono::milliseconds(500)) == boost::cv_status::timeout)
270  {
271  // this situation should never happen; if it does, the action server will be unready for goals immediately sent
272  ROS_WARN_STREAM("Timeout while waiting for control cycle to stop; immediately sent goals can get stuck");
273  return false;
274  }
275  }
276  return true;
277 }
278 
279 
281 {
283 
284  // init plan
285  std::vector<geometry_msgs::PoseStamped> plan;
286  if (!hasNewPlan())
287  {
288  setState(NO_PLAN);
289  moving_ = false;
290  ROS_ERROR("robot navigation moving has no plan!");
291  }
292 
294  int retries = 0;
295  int seq = 0;
296 
297  try
298  {
299  while (moving_ && ros::ok())
300  {
301  if (cancel_)
302  {
304  {
305  publishZeroVelocity(); // command the robot to stop on canceling navigation
306  }
308  moving_ = false;
309  condition_.notify_all();
310  return;
311  }
312 
313  if (!safetyCheck())
314  {
315  // the specific implementation must have detected a risk situation; at this abstract level, we
316  // cannot tell what the problem is, but anyway we command the robot to stop to avoid crashes
317  publishZeroVelocity(); // note that we still feedback command calculated by the plugin
318  loop_rate_.sleep();
319  }
320 
321  // update plan dynamically
322  if (hasNewPlan())
323  {
324  plan = getNewPlan();
325 
326  // check if plan is empty
327  if (plan.empty())
328  {
330  moving_ = false;
331  condition_.notify_all();
332  return;
333  }
334 
335  // check if plan could be set
336  if (!controller_->setPlan(plan))
337  {
339  moving_ = false;
340  condition_.notify_all();
341  return;
342  }
343  current_goal_pub_.publish(plan.back());
344  }
345 
346  // compute robot pose and store it in robot_pose_
347  if (!computeRobotPose())
348  {
351  moving_ = false;
352  condition_.notify_all();
353  return;
354  }
355 
356  // ask planner if the goal is reached
357  if (reachedGoalCheck())
358  {
359  ROS_DEBUG_STREAM_NAMED("abstract_controller_execution", "Reached the goal!");
361  {
363  }
365  // goal reached, tell it the controller
366  moving_ = false;
367  condition_.notify_all();
368  // if not, keep moving
369  }
370  else
371  {
373 
374  // save time and call the plugin
375  lct_mtx_.lock();
377  lct_mtx_.unlock();
378 
379  // call plugin to compute the next velocity command
380  geometry_msgs::TwistStamped cmd_vel_stamped;
381  geometry_msgs::TwistStamped robot_velocity; // TODO pass current velocity to the plugin!
382  outcome_ = computeVelocityCmd(robot_pose_, robot_velocity, cmd_vel_stamped, message_ = "");
383 
384  if (outcome_ < 10)
385  {
387  vel_pub_.publish(cmd_vel_stamped.twist);
389  retries = 0;
390  }
391  else if (outcome_ == mbf_msgs::ExePathResult::CANCELED)
392  {
393  ROS_INFO_STREAM("Controller-handled cancel completed");
394  cancel_ = true;
395  continue;
396  }
397  else
398  {
399  boost::lock_guard<boost::mutex> guard(configuration_mutex_);
400  if (max_retries_ > 0 && ++retries > max_retries_)
401  {
403  moving_ = false;
404  }
405  else if (isPatienceExceeded())
406  {
407  // patience limit enabled and running controller for more than patience without valid commands
409  moving_ = false;
410  }
411  else
412  {
413  setState(NO_LOCAL_CMD); // useful for server feedback
414  // we keep on moving if we have retries left or if the user has granted us some patience.
416  }
417  // could not compute a valid velocity command -> stop moving the robot
418  publishZeroVelocity(); // command the robot to stop; we still feedback command calculated by the plugin
419  }
420 
421  // set stamped values; timestamp and frame_id should be set by the plugin; otherwise setVelocityCmd will do
422  cmd_vel_stamped.header.seq = seq++; // sequence number
423  setVelocityCmd(cmd_vel_stamped);
424  condition_.notify_all();
425  }
426 
427  if (moving_)
428  {
429  // The nanosleep used by ROS time is not interruptable, therefore providing an interrupt point before and after
430  boost::this_thread::interruption_point();
431  if (!loop_rate_.sleep())
432  {
433  ROS_WARN_THROTTLE(1.0, "Calculation needs too much time to stay in the moving frequency! (%.4fs > %.4fs)",
435  }
436  boost::this_thread::interruption_point();
437  }
438  }
439  }
440  catch (const boost::thread_interrupted &ex)
441  {
442  // Controller thread interrupted; in most cases we have started a new plan
443  // Can also be that robot is oscillating or we have exceeded planner patience
444  ROS_DEBUG_STREAM("Controller thread interrupted!");
446  setState(STOPPED);
447  condition_.notify_all();
448  moving_ = false;
449  }
450  catch (...)
451  {
452  message_ = "Unknown error occurred: " + boost::current_exception_diagnostic_information();
455  moving_ = false;
456  condition_.notify_all();
457  }
458 }
459 
460 
462 {
463  geometry_msgs::Twist cmd_vel;
464  cmd_vel.linear.x = 0;
465  cmd_vel.linear.y = 0;
466  cmd_vel.linear.z = 0;
467  cmd_vel.angular.x = 0;
468  cmd_vel.angular.y = 0;
469  cmd_vel.angular.z = 0;
470  vel_pub_.publish(cmd_vel);
471 }
472 
473 } /* namespace mbf_abstract_nav */
mbf_abstract_nav::AbstractControllerExecution::controller_
mbf_abstract_core::AbstractController::Ptr controller_
the local planer to calculate the velocity command
Definition: abstract_controller_execution.h:224
mbf_abstract_nav::AbstractControllerExecution::getVelocityCmd
geometry_msgs::TwistStamped getVelocityCmd() const
Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method....
Definition: src/abstract_controller_execution.cpp:203
mbf_abstract_nav::AbstractControllerExecution::DEFAULT_CONTROLLER_FREQUENCY
static const double DEFAULT_CONTROLLER_FREQUENCY
Definition: abstract_controller_execution.h:79
mbf_abstract_nav::AbstractControllerExecution::tolerance_from_action_
bool tolerance_from_action_
whether check for action specific tolerance
Definition: abstract_controller_execution.h:363
mbf_abstract_nav::AbstractControllerExecution::MAX_RETRIES
@ MAX_RETRIES
Exceeded the maximum number of retries without a valid command.
Definition: abstract_controller_execution.h:140
mbf_abstract_nav::AbstractControllerExecution::last_valid_cmd_time_
ros::Time last_valid_cmd_time_
The time the controller responded with a success output (output < 10).
Definition: abstract_controller_execution.h:236
mbf_abstract_nav::AbstractControllerExecution::getNewPlan
std::vector< geometry_msgs::PoseStamped > getNewPlan()
Gets the new available plan. This method is thread safe.
Definition: src/abstract_controller_execution.cpp:160
ros::Publisher
mbf_abstract_nav::AbstractControllerExecution::ARRIVED_GOAL
@ ARRIVED_GOAL
The robot arrived the goal.
Definition: abstract_controller_execution.h:146
ros::Rate::expectedCycleTime
Duration expectedCycleTime() const
mbf_abstract_nav::AbstractControllerExecution::force_stop_at_goal_
bool force_stop_at_goal_
whether move base flex should force the robot to stop once the goal is reached.
Definition: abstract_controller_execution.h:348
mbf_abstract_nav::AbstractControllerExecution::tf_timeout_
double tf_timeout_
time before a timeout used for tf requests
Definition: abstract_controller_execution.h:336
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
mbf_abstract_nav::AbstractControllerExecution::lct_mtx_
boost::mutex lct_mtx_
mutex to handle safe thread communication for the last plugin call time
Definition: abstract_controller_execution.h:300
boost::shared_ptr< ::mbf_abstract_core::AbstractController >
mbf_abstract_nav::AbstractControllerExecution::plan_mtx_
boost::mutex plan_mtx_
mutex to handle safe thread communication for the current plan
Definition: abstract_controller_execution.h:294
mbf_abstract_nav::AbstractControllerExecution::getState
ControllerState getState() const
Return the current state of the controller execution. Thread communication safe.
Definition: src/abstract_controller_execution.cpp:126
mbf_abstract_nav::AbstractExecutionBase::cancel_
bool cancel_
flag for canceling controlling
Definition: abstract_execution_base.h:123
mbf_utility::distance
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
mbf_abstract_nav::AbstractControllerExecution::PLANNING
@ PLANNING
Executing the plugin.
Definition: abstract_controller_execution.h:138
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
mbf_abstract_nav::AbstractControllerExecution::current_goal_pub_
ros::Publisher current_goal_pub_
publisher for the current goal
Definition: abstract_controller_execution.h:330
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
mbf_abstract_nav::AbstractControllerExecution::vel_cmd_mtx_
boost::mutex vel_cmd_mtx_
mutex to handle safe thread communication for the current velocity command
Definition: abstract_controller_execution.h:297
mbf_abstract_nav::AbstractControllerExecution::INVALID_PLAN
@ INVALID_PLAN
Received an invalid plan that the controller plugin rejected.
Definition: abstract_controller_execution.h:143
mbf_abstract_nav::AbstractControllerExecution::ControllerState
ControllerState
Internal states.
Definition: abstract_controller_execution.h:134
mbf_abstract_nav::AbstractControllerExecution::angle_tolerance_
double angle_tolerance_
angle tolerance to the given goal pose
Definition: abstract_controller_execution.h:357
mbf_abstract_nav::AbstractControllerExecution::getLastPluginCallTime
ros::Time getLastPluginCallTime() const
Returns the time of the last plugin call.
Definition: src/abstract_controller_execution.cpp:209
mbf_abstract_nav::AbstractControllerExecution::robot_pose_
geometry_msgs::PoseStamped robot_pose_
current robot pose;
Definition: abstract_controller_execution.h:360
mbf_abstract_nav::AbstractExecutionBase::outcome_
uint32_t outcome_
the last received plugin execution outcome
Definition: abstract_execution_base.h:126
mbf_abstract_nav::AbstractControllerExecution::configuration_mutex_
boost::mutex configuration_mutex_
dynamic reconfigure config mutex, thread safe param reading and writing
Definition: abstract_controller_execution.h:339
mbf_abstract_nav::AbstractControllerExecution::hasNewPlan
bool hasNewPlan()
Returns true if a new plan is available, false otherwise! A new plan is set by another thread!
Definition: src/abstract_controller_execution.cpp:153
mbf_abstract_nav::AbstractControllerExecution::action_dist_tolerance_
double action_dist_tolerance_
replaces parameter dist_tolerance_ for the action
Definition: abstract_controller_execution.h:366
mbf_abstract_nav::AbstractControllerExecution::robot_frame_
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
Definition: abstract_controller_execution.h:245
mbf_abstract_nav::AbstractControllerExecution::mbf_tolerance_check_
bool mbf_tolerance_check_
whether move base flex should check for the goal tolerance or not.
Definition: abstract_controller_execution.h:345
mbf_abstract_nav
Definition: abstract_controller_execution.h:58
mbf_abstract_nav::AbstractControllerExecution::NO_PLAN
@ NO_PLAN
The controller has been started without a plan.
Definition: abstract_controller_execution.h:139
mbf_abstract_nav::AbstractControllerExecution::plan_
std::vector< geometry_msgs::PoseStamped > plan_
the last set plan which is currently processed by the controller
Definition: abstract_controller_execution.h:321
mbf_abstract_nav::AbstractControllerExecution::patience_
ros::Duration patience_
The time / duration of patience, before changing the state.
Definition: abstract_controller_execution.h:242
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
mbf_abstract_nav::AbstractControllerExecution::state_
AbstractControllerExecution::ControllerState state_
the current controller state
Definition: abstract_controller_execution.h:333
mbf_abstract_nav::AbstractControllerExecution::publishZeroVelocity
void publishZeroVelocity()
Publishes a velocity command with zero values to stop the robot.
Definition: src/abstract_controller_execution.cpp:461
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
mbf_abstract_nav::AbstractControllerExecution::reachedGoalCheck
bool reachedGoalCheck()
Checks whether the goal has been reached in the range of tolerance or not.
Definition: src/abstract_controller_execution.cpp:239
ros::ok
ROSCPP_DECL bool ok()
mbf_abstract_nav::AbstractControllerExecution::computeVelocityCmd
virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &vel_cmd, std::string &message)
Request plugin for a new velocity command, given the current position, orientation,...
Definition: src/abstract_controller_execution.cpp:183
mbf_abstract_nav::AbstractControllerExecution::vel_pub_
ros::Publisher vel_pub_
publisher for the current velocity command
Definition: abstract_controller_execution.h:327
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
mbf_abstract_nav::AbstractExecutionBase::condition_
boost::condition_variable condition_
condition variable to wake up control thread
Definition: abstract_execution_base.h:114
mbf_abstract_nav::AbstractControllerExecution::GOT_LOCAL_CMD
@ GOT_LOCAL_CMD
Got a valid velocity command from the plugin.
Definition: abstract_controller_execution.h:145
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
mbf_abstract_nav::AbstractControllerExecution::moving_
bool moving_
main controller loop variable, true if the controller is running, false otherwise
Definition: abstract_controller_execution.h:342
ROS_DEBUG
#define ROS_DEBUG(...)
mbf_abstract_nav::AbstractControllerExecution::computeRobotPose
bool computeRobotPose()
Computes the robot pose;.
Definition: src/abstract_controller_execution.cpp:168
mbf_abstract_nav::AbstractControllerExecution::INTERNAL_ERROR
@ INTERNAL_ERROR
An internal error occurred.
Definition: abstract_controller_execution.h:149
mbf_abstract_nav::AbstractControllerExecution::setControllerFrequency
bool setControllerFrequency(double frequency)
Sets the controller frequency.
Definition: src/abstract_controller_execution.cpp:83
mbf_utility::angle
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
mbf_abstract_nav::AbstractControllerExecution::EMPTY_PLAN
@ EMPTY_PLAN
Received an empty plan.
Definition: abstract_controller_execution.h:142
mbf_abstract_nav::AbstractControllerExecution::setState
void setState(ControllerState state)
Sets the controller state. This method makes the communication of the state thread safe.
Definition: src/abstract_controller_execution.cpp:120
ROS_WARN
#define ROS_WARN(...)
mbf_abstract_nav::AbstractControllerExecution::cancel
virtual bool cancel()
Cancel the controller execution. Normally called upon aborting the navigation. This calls the cancel ...
Definition: src/abstract_controller_execution.cpp:255
abstract_controller_execution.h
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::Rate::sleep
bool sleep()
mbf_abstract_nav::AbstractControllerExecution::start
virtual bool start()
Starts the controller, a valid plan should be given in advance.
Definition: src/abstract_controller_execution.cpp:108
mbf_abstract_nav::AbstractControllerExecution::~AbstractControllerExecution
virtual ~AbstractControllerExecution()
Destructor.
Definition: src/abstract_controller_execution.cpp:79
mbf_abstract_nav::AbstractControllerExecution::force_stop_on_cancel_
bool force_stop_on_cancel_
whether move base flex should force the robot to stop on canceling navigation.
Definition: abstract_controller_execution.h:351
mbf_abstract_nav::AbstractControllerExecution::last_call_time_
ros::Time last_call_time_
The current cycle start time of the last cycle run. Will by updated each cycle.
Definition: abstract_controller_execution.h:230
mbf_abstract_nav::AbstractControllerExecution::global_frame_
std::string global_frame_
the global frame the robot is controlling in.
Definition: abstract_controller_execution.h:248
ros::Time
mbf_abstract_nav::AbstractControllerExecution::setVelocityCmd
void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped)
Sets the velocity command, to make it available for another thread.
Definition: src/abstract_controller_execution.cpp:192
ros::Rate::cycleTime
Duration cycleTime() const
mbf_abstract_nav::AbstractControllerExecution::max_retries_
int max_retries_
The maximum number of retries.
Definition: abstract_controller_execution.h:239
mbf_utility::getRobotPose
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
mbf_abstract_nav::AbstractControllerExecution::AbstractControllerExecution
AbstractControllerExecution(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const MoveBaseFlexConfig &config)
Constructor.
Definition: src/abstract_controller_execution.cpp:50
mbf_abstract_nav::AbstractControllerExecution::start_time_
ros::Time start_time_
The time the controller has been started.
Definition: abstract_controller_execution.h:233
mbf_abstract_nav::AbstractExecutionBase::message_
std::string message_
the last received plugin execution message
Definition: abstract_execution_base.h:129
mbf_abstract_nav::AbstractControllerExecution::NO_LOCAL_CMD
@ NO_LOCAL_CMD
Received no velocity command by the plugin, in the current cycle.
Definition: abstract_controller_execution.h:144
mbf_abstract_nav::AbstractControllerExecution::STOPPED
@ STOPPED
The controller has been stopped!
Definition: abstract_controller_execution.h:148
ROS_ERROR
#define ROS_ERROR(...)
mbf_abstract_nav::AbstractControllerExecution::run
virtual void run()
The main run method, a thread will execute this method. It contains the main controller execution loo...
Definition: src/abstract_controller_execution.cpp:280
mbf_abstract_nav::AbstractControllerExecution::CANCELED
@ CANCELED
The controller has been canceled.
Definition: abstract_controller_execution.h:147
mbf_abstract_nav::AbstractControllerExecution::vel_cmd_stamped_
geometry_msgs::TwistStamped vel_cmd_stamped_
the last calculated velocity command
Definition: abstract_controller_execution.h:318
mbf_abstract_nav::AbstractControllerExecution::loop_rate_
ros::Rate loop_rate_
the loop_rate which corresponds with the controller frequency.
Definition: abstract_controller_execution.h:324
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mbf_abstract_nav::AbstractControllerExecution::STARTED
@ STARTED
Controller has been started.
Definition: abstract_controller_execution.h:137
mbf_abstract_nav::AbstractControllerExecution::tf_listener_ptr
const TFPtr & tf_listener_ptr
shared pointer to the shared tf listener
Definition: abstract_controller_execution.h:227
ros::Rate
mbf_abstract_nav::AbstractControllerExecution::dist_tolerance_
double dist_tolerance_
distance tolerance to the given goal pose
Definition: abstract_controller_execution.h:354
mbf_abstract_nav::AbstractExecutionBase
Base class for running concurrent navigation tasks.
Definition: abstract_execution_base.h:57
mbf_abstract_nav::AbstractControllerExecution::new_plan_
bool new_plan_
true, if a new plan is available. See hasNewPlan()!
Definition: abstract_controller_execution.h:303
DurationBase< Duration >::toSec
double toSec() const
mbf_abstract_nav::AbstractControllerExecution::safetyCheck
virtual bool safetyCheck()
Check if its safe to drive. This method gets called at every controller cycle, stopping the robot if ...
Definition: abstract_controller_execution.h:262
mbf_abstract_nav::AbstractControllerExecution::reconfigure
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
Definition: src/abstract_controller_execution.cpp:95
mbf_abstract_nav::AbstractExecutionBase::waitForStateUpdate
boost::cv_status waitForStateUpdate(boost::chrono::microseconds const &duration)
Definition: src/abstract_execution_base.cpp:82
ROS_INFO
#define ROS_INFO(...)
mbf_abstract_nav::AbstractControllerExecution::setNewPlan
void setNewPlan(const std::vector< geometry_msgs::PoseStamped > &plan, bool tolerance_from_action=false, double action_dist_tolerance=1.0, double action_angle_tolerance=3.1415)
Sets a new plan to the controller execution.
Definition: src/abstract_controller_execution.cpp:132
mbf_abstract_nav::AbstractControllerExecution::state_mtx_
boost::mutex state_mtx_
mutex to handle safe thread communication for the current value of the state
Definition: abstract_controller_execution.h:291
mbf_abstract_nav::AbstractControllerExecution::PAT_EXCEEDED
@ PAT_EXCEEDED
Exceeded the patience time without a valid command.
Definition: abstract_controller_execution.h:141
ros::Duration
mbf_abstract_nav::AbstractControllerExecution::action_angle_tolerance_
double action_angle_tolerance_
replaces parameter angle_tolerance_ for the action
Definition: abstract_controller_execution.h:369
mbf_abstract_nav::AbstractExecutionBase::start
virtual bool start()
Definition: src/abstract_execution_base.cpp:57
mbf_abstract_nav::AbstractControllerExecution::isMoving
bool isMoving() const
Returns whether the robot should normally move or not. True if the controller seems to work properly.
Definition: src/abstract_controller_execution.cpp:234
DurationBase< Duration >::isZero
bool isZero() const
mbf_abstract_nav::AbstractExecutionBase::name_
std::string name_
the plugin name; not the plugin type!
Definition: abstract_execution_base.h:132
mbf_abstract_nav::AbstractControllerExecution::isPatienceExceeded
bool isPatienceExceeded() const
Checks whether the patience duration time has been exceeded, ot not.
Definition: src/abstract_controller_execution.cpp:215
ros::NodeHandle
ros::Time::now
static Time now()


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47