Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
00042 #define MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_
00043
00044 #include <map>
00045 #include <stdint.h>
00046 #include <string>
00047 #include <vector>
00048
00049 #include <tf/transform_listener.h>
00050 #include <geometry_msgs/PoseStamped.h>
00051 #include <geometry_msgs/Twist.h>
00052
00053 #include <mbf_utility/navigation_utility.h>
00054 #include <mbf_abstract_core/abstract_controller.h>
00055 #include <mbf_utility/types.h>
00056
00057 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
00058 #include "mbf_abstract_nav/abstract_execution_base.h"
00059
00060 namespace mbf_abstract_nav
00061 {
00076 class AbstractControllerExecution : public AbstractExecutionBase
00077 {
00078 public:
00079
00080 static const double DEFAULT_CONTROLLER_FREQUENCY;
00081
00082 typedef boost::shared_ptr<AbstractControllerExecution > Ptr;
00083
00090 AbstractControllerExecution(
00091 const std::string name,
00092 const mbf_abstract_core::AbstractController::Ptr& controller_ptr,
00093 const ros::Publisher& vel_pub,
00094 const ros::Publisher& goal_pub,
00095 const TFPtr &tf_listener_ptr,
00096 const MoveBaseFlexConfig &config,
00097 boost::function<void()> setup_fn,
00098 boost::function<void()> cleanup_fn);
00099
00103 virtual ~AbstractControllerExecution();
00104
00109 virtual bool start();
00110
00115 void setNewPlan(const std::vector<geometry_msgs::PoseStamped> &plan);
00116
00122 virtual bool cancel();
00123
00127 enum ControllerState
00128 {
00129 INITIALIZED,
00130 STARTED,
00131 PLANNING,
00132 NO_PLAN,
00133 MAX_RETRIES,
00134 PAT_EXCEEDED,
00135 EMPTY_PLAN,
00136 INVALID_PLAN,
00137 NO_LOCAL_CMD,
00138 GOT_LOCAL_CMD,
00139 ARRIVED_GOAL,
00140 CANCELED,
00141 STOPPED,
00142 INTERNAL_ERROR
00143 };
00144
00149 ControllerState getState();
00150
00155 ros::Time getLastPluginCallTime();
00156
00163 geometry_msgs::TwistStamped getVelocityCmd();
00164
00169 bool isPatienceExceeded();
00170
00176 bool setControllerFrequency(double frequency);
00177
00183 void reconfigure(const MoveBaseFlexConfig &config);
00184
00189 bool isMoving();
00190
00191 protected:
00192
00203 virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped& pose,
00204 const geometry_msgs::TwistStamped& velocity,
00205 geometry_msgs::TwistStamped& vel_cmd, std::string& message);
00206
00211 void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped);
00212
00214 std::string plugin_name_;
00215
00217 mbf_abstract_core::AbstractController::Ptr controller_;
00218
00220 const TFPtr &tf_listener_ptr;
00221
00223 ros::Time last_call_time_;
00224
00226 ros::Time start_time_;
00227
00229 int max_retries_;
00230
00232 ros::Duration patience_;
00233
00237 virtual void run();
00238
00239 private:
00240
00241
00245 void publishZeroVelocity();
00246
00251 bool reachedGoalCheck();
00252
00257 bool computeRobotPose();
00258
00263 void setState(ControllerState state);
00264
00266 boost::mutex state_mtx_;
00267
00269 boost::mutex plan_mtx_;
00270
00272 boost::mutex vel_cmd_mtx_;
00273
00275 boost::mutex lct_mtx_;
00276
00278 bool new_plan_;
00279
00284 bool hasNewPlan();
00285
00290 std::vector<geometry_msgs::PoseStamped> getNewPlan();
00291
00293 geometry_msgs::TwistStamped vel_cmd_stamped_;
00294
00296 std::vector<geometry_msgs::PoseStamped> plan_;
00297
00299 boost::chrono::microseconds calling_duration_;
00300
00302 std::string robot_frame_;
00303
00305 std::string global_frame_;
00306
00308 ros::Publisher vel_pub_;
00309
00311 ros::Publisher current_goal_pub_;
00312
00314 AbstractControllerExecution::ControllerState state_;
00315
00317 double tf_timeout_;
00318
00320 boost::mutex configuration_mutex_;
00321
00323 bool moving_;
00324
00326 bool mbf_tolerance_check_;
00327
00329 double dist_tolerance_;
00330
00332 double angle_tolerance_;
00333
00335 geometry_msgs::PoseStamped robot_pose_;
00336
00337 };
00338
00339 }
00340
00341 #endif