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 namespace eband_local_planner{
00065
00070 class EBandTrajectoryCtrl{
00071
00072 public:
00073
00077 EBandTrajectoryCtrl();
00078
00084 EBandTrajectoryCtrl(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00085
00089 ~EBandTrajectoryCtrl();
00090
00096 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00097
00102 void setVisualization(boost::shared_ptr<EBandVisualization> target_visual);
00103
00108 bool setBand(const std::vector<Bubble>& elastic_band);
00109
00114 bool setOdometry(const nav_msgs::Odometry& odometry);
00115
00120 bool getTwist(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
00121 bool getTwistDifferentialDrive(geometry_msgs::Twist& twist_cmd, bool& goal_reached);
00122
00123 private:
00124
00125
00126 costmap_2d::Costmap2DROS* costmap_ros_;
00127 boost::shared_ptr<EBandVisualization> target_visual_;
00128
00129 control_toolbox::Pid pid_;
00130
00131
00132 bool differential_drive_hack_;
00133 double k_p_, k_nu_, k_int_, k_diff_, ctrl_freq_;
00134 double acc_max_, virt_mass_;
00135 double max_vel_lin_, max_vel_th_, min_vel_lin_, min_vel_th_;
00136 double min_in_place_vel_th_;
00137 double in_place_trans_vel_;
00138 double tolerance_trans_, tolerance_rot_, tolerance_timeout_;
00139 double acc_max_trans_, acc_max_rot_;
00140 double rotation_correction_threshold_;
00141
00142
00143 double bubble_velocity_multiplier_;
00144 double rotation_threshold_multiplier_;
00145 bool disallow_hysteresis_;
00146 bool in_final_goal_turn_;
00147
00148
00149 bool initialized_, band_set_, visualization_;
00150
00151
00152 std::vector<Bubble> elastic_band_;
00153 geometry_msgs::Twist odom_vel_;
00154 geometry_msgs::Twist last_vel_;
00155 geometry_msgs::Pose ref_frame_band_;
00156
00158 inline double sign(double n)
00159 {
00160 return n < 0.0 ? -1.0 : 1.0;
00161 }
00162
00170 geometry_msgs::Twist getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame);
00171 geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame);
00172
00180 geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist, const geometry_msgs::Pose& frame1,
00181 const geometry_msgs::Pose& frame2);
00182
00188 geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00189
00196 double getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir);
00197
00198 };
00199 };
00200 #endif
00201
00202
00203
00204
00205
00206