Go to the documentation of this file.
41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
48 #include <geometry_msgs/PoseStamped.h>
49 #include <geometry_msgs/Twist.h>
55 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
90 const std::string &name,
95 const MoveBaseFlexConfig &config);
106 virtual bool start();
116 const std::vector<geometry_msgs::PoseStamped> &plan,
117 bool tolerance_from_action =
false,
118 double action_dist_tolerance = 1.0,
119 double action_angle_tolerance = 3.1415);
190 void reconfigure(
const MoveBaseFlexConfig &config);
211 const geometry_msgs::TwistStamped &velocity,
212 geometry_msgs::TwistStamped &vel_cmd, std::string &message);
218 void setVelocityCmd(
const geometry_msgs::TwistStamped &vel_cmd_stamped);
315 std::vector<geometry_msgs::PoseStamped>
getNewPlan();
321 std::vector<geometry_msgs::PoseStamped>
plan_;
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.
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
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.
@ PLANNING
Executing the plugin.
ros::Publisher current_goal_pub_
publisher for the current goal
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;
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.
AbstractControllerExecution::ControllerState state_
the current controller state
void publishZeroVelocity()
Publishes a velocity command with zero values to stop the robot.
boost::shared_ptr< AbstractControllerExecution > Ptr
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
@ GOT_LOCAL_CMD
Got a valid velocity command from the plugin.
@ INITIALIZED
Controller has been initialized successfully.
bool moving_
main controller loop variable, true if the controller is running, false otherwise
std::string plugin_name_
the name of the loaded plugin
bool computeRobotPose()
Computes the robot pose;.
@ INTERNAL_ERROR
An internal error occurred.
bool setControllerFrequency(double frequency)
Sets the controller frequency.
@ 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 ...
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.
int max_retries_
The maximum number of retries.
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.
@ 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.
@ 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...
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.
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
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.
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