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 #ifndef EBAND_TRAJECTORY_CONTROLLER_H_
00039 #define EBAND_TRAJECTORY_CONTROLLER_H_
00040 
00041 #include <ros/ros.h>
00042 #include <ros/assert.h>
00043 
00044 
00045 #include <eband_local_planner/conversions_and_types.h>
00046 #include <eband_local_planner/eband_visualization.h>
00047 
00048 
00049 #include <geometry_msgs/PoseStamped.h>
00050 #include <geometry_msgs/Pose.h>
00051 #include <geometry_msgs/Pose2D.h>
00052 #include <geometry_msgs/Twist.h>
00053 
00054 
00055 #include <nav_msgs/Odometry.h>
00056 
00057 
00058 #include <angles/angles.h>
00059 #include <tf/tf.h>
00060 
00061 
00062 #include <control_toolbox/pid.h>
00063 
00064 
00065 namespace eband_local_planner{
00066 
00067 
00072 class EBandTrajectoryCtrl{
00073 
00074         public:
00075 
00079                 EBandTrajectoryCtrl();
00080 
00086                 EBandTrajectoryCtrl(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00087 
00091                 ~EBandTrajectoryCtrl();
00092 
00098                 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00099 
00104                 void setVisualization(boost::shared_ptr<EBandVisualization> target_visual);
00105 
00110                 bool setBand(const std::vector<Bubble>& elastic_band);
00111 
00116                 bool setOdometry(const nav_msgs::Odometry& odometry);
00117 
00122                 bool getTwist(geometry_msgs::Twist& twist_cmd);
00123 
00124 
00125         private:
00126 
00127                 
00128                 costmap_2d::Costmap2DROS* costmap_ros_; 
00129                 boost::shared_ptr<EBandVisualization> target_visual_; 
00130 
00131     control_toolbox::Pid pid_;
00132 
00133                 
00134                 double k_p_, k_nu_, ctrl_freq_;
00135                 double acc_max_, virt_mass_;
00136                 double max_vel_lin_, max_vel_th_, min_vel_lin_, min_vel_th_;
00137                 double min_in_place_vel_th_;
00138                 double in_place_trans_vel_;
00139                 double tolerance_trans_, tolerance_rot_, tolerance_timeout_;
00140                 double acc_max_trans_, acc_max_rot_;
00141                 double rotation_correction_threshold_; 
00142 
00143                 
00144                 bool initialized_, band_set_, visualization_;
00145 
00146                 
00147                 std::vector<Bubble> elastic_band_;
00148                 geometry_msgs::Twist odom_vel_;
00149                 geometry_msgs::Twist last_vel_;
00150                 geometry_msgs::Pose ref_frame_band_;
00151 
00153                 inline double sign(double n)
00154                 {
00155                         return n < 0.0 ? -1.0 : 1.0;
00156                 }
00157 
00165                 geometry_msgs::Twist getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame);
00166                 
00174                 geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist, const geometry_msgs::Pose& frame1,
00175                                                                                                                                 const geometry_msgs::Pose& frame2);
00176 
00182                 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00183 
00190                 double getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir);
00191 
00192 };
00193 };
00194 #endif
00195 
00196 
00197 
00198 
00199 
00200