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_LOCAL_PLANNER_H_
00039 #define EBAND_LOCAL_PLANNER_H_
00040
00041
00042
00043 #include <ros/ros.h>
00044 #include <ros/assert.h>
00045
00046
00047 #include <eband_local_planner/conversions_and_types.h>
00048 #include <eband_local_planner/eband_visualization.h>
00049
00050
00051 #include <base_local_planner/costmap_model.h>
00052
00053
00054 #include <nav_msgs/Path.h>
00055 #include <nav_msgs/Odometry.h>
00056 #include <geometry_msgs/PoseStamped.h>
00057 #include <geometry_msgs/Pose.h>
00058 #include <geometry_msgs/Pose2D.h>
00059 #include <geometry_msgs/Twist.h>
00060 #include <geometry_msgs/WrenchStamped.h>
00061
00062
00063 #include <angles/angles.h>
00064 #include <tf/tf.h>
00065
00066
00067 #include <costmap_2d/costmap_2d_ros.h>
00068
00069
00070 #include <boost/shared_ptr.hpp>
00071
00072 namespace eband_local_planner{
00073
00078 class EBandPlanner{
00079
00080 public:
00084 EBandPlanner();
00085
00091 EBandPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00092
00096 ~EBandPlanner();
00097
00103 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00104
00109 void setVisualization(boost::shared_ptr<EBandVisualization> eband_visual);
00110
00116 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
00117
00123 bool getPlan(std::vector<geometry_msgs::PoseStamped>& global_plan);
00124
00130 bool getBand(std::vector<Bubble>& elastic_band);
00131
00137 bool addFrames(const std::vector<geometry_msgs::PoseStamped>& robot_pose, const AddAtPosition& add_frames_at);
00138
00143 bool optimizeBand();
00144
00150 bool optimizeBand(std::vector<Bubble>& band);
00151
00152 private:
00153
00154 costmap_2d::Costmap2DROS* costmap_ros_;
00155
00156
00157 std::vector<double> acc_lim_;
00158 int num_optim_iterations_;
00159 double internal_force_gain_;
00160 double external_force_gain_;
00161 double tiny_bubble_distance_;
00162 double tiny_bubble_expansion_;
00163 double min_bubble_overlap_;
00164 int max_recursion_depth_approx_equi_;
00165 double equilibrium_relative_overshoot_;
00166 double significant_force_;
00167 double costmap_weight_;
00168
00169
00170 base_local_planner::CostmapModel* world_model_;
00171 boost::shared_ptr<EBandVisualization> eband_visual_;
00172
00173
00174 bool initialized_, visualization_;
00175
00176
00177 std::vector<geometry_msgs::Point> footprint_spec_;
00178 costmap_2d::Costmap2D* costmap_;
00179 std::vector<geometry_msgs::PoseStamped> global_plan_;
00180 std::vector<Bubble> elastic_band_;
00181
00182
00183
00184
00185
00186
00192 bool refineBand(std::vector<Bubble>& band);
00193
00194
00202 bool removeAndFill(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter);
00203
00204
00212 bool fillGap(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter);
00213
00214
00215
00216
00222 bool modifyBandArtificialForce(std::vector<Bubble>& band);
00223
00224
00232 bool applyForces(int bubble_num, std::vector<Bubble>& band, std::vector<geometry_msgs::WrenchStamped> forces);
00233
00234
00244 bool moveApproximateEquilibrium(const int& bubble_num, const std::vector<Bubble>& band, Bubble& curr_bubble,
00245 const geometry_msgs::WrenchStamped& curr_bubble_force, geometry_msgs::Twist& curr_step_width,
00246 const int& curr_recursion_depth);
00247
00248
00249
00250
00258 bool interpolateBubbles(geometry_msgs::PoseStamped start_center, geometry_msgs::PoseStamped end_center, geometry_msgs::PoseStamped& interpolated_center);
00259
00260
00268 bool checkOverlap(Bubble bubble1, Bubble bubble2);
00269
00270
00278 bool calcBubbleDistance(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, double& distance);
00279
00280
00288 bool calcBubbleDifference(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, geometry_msgs::Twist& difference);
00289
00290
00297 bool calcObstacleKinematicDistance(geometry_msgs::Pose center_pose, double& distance);
00298
00299
00308 bool getForcesAt(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces);
00309
00310
00319 bool calcInternalForces(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces);
00320
00321
00329 bool calcExternalForces(int bubble_num, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces);
00330
00331
00338 bool suppressTangentialForces(int bubble_num, std::vector<Bubble> band, geometry_msgs::WrenchStamped& forces);
00339
00340
00341
00342
00349 bool convertPlanToBand(std::vector<geometry_msgs::PoseStamped> plan, std::vector<Bubble>& band);
00350
00351
00358 bool convertBandToPlan(std::vector<geometry_msgs::PoseStamped>& plan, std::vector<Bubble> band);
00359
00360 };
00361 };
00362 #endif