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 #include <eband_local_planner/EBandPlannerConfig.h>
00048
00049
00050 #include <geometry_msgs/PoseStamped.h>
00051 #include <geometry_msgs/Pose.h>
00052 #include <geometry_msgs/Pose2D.h>
00053 #include <geometry_msgs/Twist.h>
00054
00055
00056 #include <nav_msgs/Odometry.h>
00057
00058
00059 #include <angles/angles.h>
00060 #include <tf/tf.h>
00061
00062
00063 #include <control_toolbox/pid.h>
00064
00065 namespace eband_local_planner{
00066
00071 class EBandTrajectoryCtrl{
00072
00073 public:
00074
00078 EBandTrajectoryCtrl();
00079
00085 EBandTrajectoryCtrl(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00086
00090 ~EBandTrajectoryCtrl();
00091
00097 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00098
00099
00104 void reconfigure(EBandPlannerConfig& config);
00105
00110 void setVisualization(boost::shared_ptr<EBandVisualization> target_visual);
00111
00116 bool setBand(const std::vector<Bubble>& elastic_band);
00117
00122 bool setOdometry(const nav_msgs::Odometry& odometry);
00123
00128 bool getTwist(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
00129 bool getTwistDifferentialDrive(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
00130
00131 private:
00132
00133
00134 costmap_2d::Costmap2DROS* costmap_ros_;
00135 boost::shared_ptr<EBandVisualization> target_visual_;
00136
00137 control_toolbox::Pid pid_;
00138
00139
00140 bool differential_drive_hack_;
00141 double k_p_, k_nu_, ctrl_freq_;
00142 double acc_max_, virt_mass_;
00143 double max_vel_lin_, max_vel_th_, min_vel_lin_, min_vel_th_;
00144 double min_in_place_vel_th_;
00145 double in_place_trans_vel_;
00146 double tolerance_trans_, tolerance_rot_;
00147 double acc_max_trans_, acc_max_rot_;
00148 double rotation_correction_threshold_;
00149
00150
00151 double bubble_velocity_multiplier_;
00152 double rotation_threshold_multiplier_;
00153 bool disallow_hysteresis_;
00154 bool in_final_goal_turn_;
00155
00156
00157 bool initialized_, band_set_, visualization_;
00158
00159
00160 std::vector<Bubble> elastic_band_;
00161 geometry_msgs::Twist odom_vel_;
00162 geometry_msgs::Twist last_vel_;
00163 geometry_msgs::Pose ref_frame_band_;
00164
00166 inline double sign(double n)
00167 {
00168 return n < 0.0 ? -1.0 : 1.0;
00169 }
00170
00178 geometry_msgs::Twist getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame);
00179 geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame);
00180
00188 geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist, const geometry_msgs::Pose& frame1,
00189 const geometry_msgs::Pose& frame2);
00190
00196 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00197
00204 double getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir);
00205
00206 };
00207 };
00208 #endif
00209
00210
00211
00212
00213
00214