41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ 42 #define MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ 50 #include <geometry_msgs/PoseStamped.h> 51 #include <geometry_msgs/Twist.h> 57 #include "mbf_abstract_nav/MoveBaseFlexConfig.h" 91 const std::string name,
96 const MoveBaseFlexConfig &config,
97 boost::function<
void()> setup_fn,
98 boost::function<
void()> cleanup_fn);
109 virtual bool start();
115 void setNewPlan(
const std::vector<geometry_msgs::PoseStamped> &plan);
183 void reconfigure(
const MoveBaseFlexConfig &config);
204 const geometry_msgs::TwistStamped& velocity,
205 geometry_msgs::TwistStamped& vel_cmd, std::string& message);
211 void setVelocityCmd(
const geometry_msgs::TwistStamped &vel_cmd_stamped);
290 std::vector<geometry_msgs::PoseStamped>
getNewPlan();
296 std::vector<geometry_msgs::PoseStamped>
plan_;
boost::mutex plan_mtx_
mutex to handle safe thread communication for the current plan
ControllerState
Internal states.
bool new_plan_
true, if a new plan is available. See hasNewPlan()!
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, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
Constructor.
std::string global_frame_
the global frame the robot is controlling in.
virtual ~AbstractControllerExecution()
Destructor.
boost::chrono::microseconds calling_duration_
the duration which corresponds with the controller frequency.
ros::Duration patience_
The time / duration of patience, before changing the state.
boost::mutex configuration_mutex_
dynamic reconfigure config mutex, thread safe param reading and writing
bool computeRobotPose()
Computes the robot pose;.
boost::mutex vel_cmd_mtx_
mutex to handle safe thread communication for the current velocity command
The controller has been stopped!
Exceeded the maximum number of retries without a valid command.
Received no velocity command by the plugin, in the current cycle.
ros::Publisher current_goal_pub_
publisher for the current goal
Got a valid velocity command from the plugin.
bool hasNewPlan()
Returns true if a new plan is available, false otherwise! A new plan is set by another thread! ...
void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped)
Sets the velocity command, to make it available for another thread.
double dist_tolerance_
distance tolerance to the given goal pose
The controller has been started without a plan.
void setState(ControllerState state)
Sets the controller state. This method makes the communication of the state thread safe...
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
ros::Publisher vel_pub_
publisher for the current velocity command
const TFPtr & tf_listener_ptr
shared pointer to the shared tf listener
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
static const double DEFAULT_CONTROLLER_FREQUENCY
virtual void run()
The main run method, a thread will execute this method. It contains the main controller execution loo...
boost::shared_ptr< AbstractControllerExecution > Ptr
geometry_msgs::TwistStamped vel_cmd_stamped_
the last calculated velocity command
Exceeded the patience time without a valid command.
bool isMoving()
Returns whether the robot should normally move or not. True if the controller seems to work properly...
bool mbf_tolerance_check_
whether move base flex should check for the goal tolerance or not.
AbstractControllerExecution::ControllerState state_
the current controller state
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 isPatienceExceeded()
Checks whether the patience duration time has been exceeded, ot not.
double angle_tolerance_
angle tolerance to the given goal pose
Controller has been initialized successfully.
boost::mutex state_mtx_
mutex to handle safe thread communication for the current value of the state
The robot arrived the goal.
ros::Time getLastPluginCallTime()
Returns the time of the last plugin call.
An internal error occurred.
ros::Time start_time_
The time the controller has been started.
std::vector< geometry_msgs::PoseStamped > getNewPlan()
Gets the new available plan. This method is thread safe.
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, and velocity of the robot. We use this virtual method to give concrete implementations as move_base the chance to override it and do additional stuff, for example locking the costmap.
Received an invalid plan that the controller plugin rejected.
geometry_msgs::TwistStamped getVelocityCmd()
Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method...
void publishZeroVelocity()
bool reachedGoalCheck()
Checks whether the goal has been reached in the range of tolerance or not.
mbf_abstract_core::AbstractController::Ptr controller_
the local planer to calculate the velocity command
int max_retries_
The maximum number of retries.
ControllerState getState()
Return the current state of the controller execution. Thread communication safe.
boost::mutex lct_mtx_
mutex to handle safe thread communication for the last plugin call time
geometry_msgs::PoseStamped robot_pose_
current robot pose;
std::string robot_frame_
the frame of the robot, which will be used to determine its position.
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
virtual bool start()
Starts the controller, a valid plan should be given in advance.
double tf_timeout_
time before a timeout used for tf requests
bool setControllerFrequency(double frequency)
Sets the controller frequency.
Controller has been started.
std::vector< geometry_msgs::PoseStamped > plan_
the last set plan which is currently processed by the controller
ros::Time last_call_time_
The current cycle start time of the last cycle run. Will by updated each cycle.
void setNewPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Sets a new plan to the controller execution.
The controller has been canceled.