Go to the documentation of this file.
   41 #include <mbf_msgs/ExePathResult.h> 
   51     const std::string &name,
 
   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)
 
   88     ROS_ERROR(
"Controller frequency must be greater than 0.0! No change of the frequency!");
 
  122   boost::lock_guard<boost::mutex> guard(
state_mtx_);
 
  128   boost::lock_guard<boost::mutex> guard(
state_mtx_);
 
  133   const std::vector<geometry_msgs::PoseStamped> &plan,
 
  134   bool tolerance_from_action,
 
  135   double action_dist_tolerance,
 
  136   double action_angle_tolerance)
 
  141     ROS_DEBUG(
"Setting new plan while moving");
 
  143   boost::lock_guard<boost::mutex> guard(
plan_mtx_);
 
  155   boost::lock_guard<boost::mutex> guard(
plan_mtx_);
 
  162   boost::lock_guard<boost::mutex> guard(
plan_mtx_);
 
  173     ROS_ERROR_STREAM(
"Could not get the robot pose in the global frame. - robot frame: \"" 
  175     message_ = 
"Could not get the robot pose";
 
  176     outcome_ = mbf_msgs::ExePathResult::TF_ERROR;
 
  184                                                          const geometry_msgs::TwistStamped &robot_velocity,
 
  185                                                          geometry_msgs::TwistStamped &vel_cmd,
 
  186                                                          std::string &message)
 
  188   return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
 
  211   boost::lock_guard<boost::mutex> guard(
lct_mtx_);
 
  217   boost::lock_guard<boost::mutex> guard(
lct_mtx_);
 
  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!");
 
  262     ROS_INFO(
"Controller will take care of stopping");
 
  266     ROS_WARN(
"Controller defers handling cancel; force it and wait until the current control cycle finished");
 
  269     if (
waitForStateUpdate(boost::chrono::milliseconds(500)) == boost::cv_status::timeout)
 
  272       ROS_WARN_STREAM(
"Timeout while waiting for control cycle to stop; immediately sent goals can get stuck");
 
  285   std::vector<geometry_msgs::PoseStamped> plan;
 
  290     ROS_ERROR(
"robot navigation moving has no plan!");
 
  380         geometry_msgs::TwistStamped cmd_vel_stamped;
 
  381         geometry_msgs::TwistStamped robot_velocity;   
 
  391         else if (
outcome_ == mbf_msgs::ExePathResult::CANCELED)
 
  422         cmd_vel_stamped.header.seq = seq++; 
 
  430         boost::this_thread::interruption_point();
 
  433           ROS_WARN_THROTTLE(1.0, 
"Calculation needs too much time to stay in the moving frequency! (%.4fs > %.4fs)",
 
  436         boost::this_thread::interruption_point();
 
  440   catch (
const boost::thread_interrupted &ex)
 
  452     message_ = 
"Unknown error occurred: " + boost::current_exception_diagnostic_information();
 
  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;
 
  
mbf_abstract_core::AbstractController::Ptr controller_
the local planer to calculate the velocity command
geometry_msgs::TwistStamped getVelocityCmd() const
Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method....
static const double DEFAULT_CONTROLLER_FREQUENCY
bool tolerance_from_action_
whether check for action specific tolerance
@ MAX_RETRIES
Exceeded the maximum number of retries without a valid command.
ros::Time last_valid_cmd_time_
The time the controller responded with a success output (output < 10).
std::vector< geometry_msgs::PoseStamped > getNewPlan()
Gets the new available plan. This method is thread safe.
@ ARRIVED_GOAL
The robot arrived the goal.
Duration expectedCycleTime() const
bool force_stop_at_goal_
whether move base flex should force the robot to stop once the goal is reached.
double tf_timeout_
time before a timeout used for tf requests
#define ROS_ERROR_STREAM(args)
boost::mutex lct_mtx_
mutex to handle safe thread communication for the last plugin call time
boost::mutex plan_mtx_
mutex to handle safe thread communication for the current plan
ControllerState getState() const
Return the current state of the controller execution. Thread communication safe.
bool cancel_
flag for canceling controlling
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
@ PLANNING
Executing the plugin.
#define ROS_DEBUG_STREAM_NAMED(name, args)
ros::Publisher current_goal_pub_
publisher for the current goal
#define ROS_FATAL_STREAM(args)
#define ROS_WARN_THROTTLE(period,...)
boost::mutex vel_cmd_mtx_
mutex to handle safe thread communication for the current velocity command
@ INVALID_PLAN
Received an invalid plan that the controller plugin rejected.
ControllerState
Internal states.
double angle_tolerance_
angle tolerance to the given goal pose
ros::Time getLastPluginCallTime() const
Returns the time of the last plugin call.
geometry_msgs::PoseStamped robot_pose_
current robot pose;
uint32_t outcome_
the last received plugin execution outcome
boost::mutex configuration_mutex_
dynamic reconfigure config mutex, thread safe param reading and writing
bool hasNewPlan()
Returns true if a new plan is available, false otherwise! A new plan is set by another thread!
double action_dist_tolerance_
replaces parameter dist_tolerance_ for the action
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
bool mbf_tolerance_check_
whether move base flex should check for the goal tolerance or not.
@ NO_PLAN
The controller has been started without a plan.
std::vector< geometry_msgs::PoseStamped > plan_
the last set plan which is currently processed by the controller
ros::Duration patience_
The time / duration of patience, before changing the state.
#define ROS_DEBUG_STREAM(args)
AbstractControllerExecution::ControllerState state_
the current controller state
void publishZeroVelocity()
Publishes a velocity command with zero values to stop the robot.
void publish(const boost::shared_ptr< M > &message) const
bool reachedGoalCheck()
Checks whether the goal has been reached in the range of tolerance or not.
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,...
ros::Publisher vel_pub_
publisher for the current velocity command
#define ROS_WARN_STREAM(args)
boost::condition_variable condition_
condition variable to wake up control thread
@ GOT_LOCAL_CMD
Got a valid velocity command from the plugin.
#define ROS_WARN_STREAM_THROTTLE(period, args)
bool moving_
main controller loop variable, true if the controller is running, false otherwise
bool computeRobotPose()
Computes the robot pose;.
@ INTERNAL_ERROR
An internal error occurred.
bool setControllerFrequency(double frequency)
Sets the controller frequency.
double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
@ EMPTY_PLAN
Received an empty plan.
void setState(ControllerState state)
Sets the controller state. This method makes the communication of the state thread safe.
virtual bool cancel()
Cancel the controller execution. Normally called upon aborting the navigation. This calls the cancel ...
#define ROS_INFO_STREAM(args)
virtual bool start()
Starts the controller, a valid plan should be given in advance.
virtual ~AbstractControllerExecution()
Destructor.
bool force_stop_on_cancel_
whether move base flex should force the robot to stop on canceling navigation.
ros::Time last_call_time_
The current cycle start time of the last cycle run. Will by updated each cycle.
std::string global_frame_
the global frame the robot is controlling in.
void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped)
Sets the velocity command, to make it available for another thread.
Duration cycleTime() const
int max_retries_
The maximum number of retries.
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
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.
ros::Time start_time_
The time the controller has been started.
std::string message_
the last received plugin execution message
@ NO_LOCAL_CMD
Received no velocity command by the plugin, in the current cycle.
@ STOPPED
The controller has been stopped!
virtual void run()
The main run method, a thread will execute this method. It contains the main controller execution loo...
@ CANCELED
The controller has been canceled.
geometry_msgs::TwistStamped vel_cmd_stamped_
the last calculated velocity command
ros::Rate loop_rate_
the loop_rate which corresponds with the controller frequency.
T param(const std::string ¶m_name, const T &default_val) const
@ STARTED
Controller has been started.
const TFPtr & tf_listener_ptr
shared pointer to the shared tf listener
double dist_tolerance_
distance tolerance to the given goal pose
Base class for running concurrent navigation tasks.
bool new_plan_
true, if a new plan is available. See hasNewPlan()!
virtual bool safetyCheck()
Check if its safe to drive. This method gets called at every controller cycle, stopping the robot if ...
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
boost::cv_status waitForStateUpdate(boost::chrono::microseconds const &duration)
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.
boost::mutex state_mtx_
mutex to handle safe thread communication for the current value of the state
@ PAT_EXCEEDED
Exceeded the patience time without a valid command.
double action_angle_tolerance_
replaces parameter angle_tolerance_ for the action
bool isMoving() const
Returns whether the robot should normally move or not. True if the controller seems to work properly.
std::string name_
the plugin name; not the plugin type!
bool isPatienceExceeded() const
Checks whether the patience duration time has been exceeded, ot not.
mbf_abstract_nav
Author(s): Sebastian Pütz 
autogenerated on Wed Mar 2 2022 00:33:47