stepback_and_steerturn_recovery.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00035 #ifndef STEPBACK_AND_STEERTURN_RECOVERY_H
00036 #define STEPBACK_AND_STEERTURN_RECOVERY_H
00037 
00038 #include <nav_core/recovery_behavior.h>
00039 #include <base_local_planner/costmap_model.h>
00040 #include <costmap_2d/costmap_2d_ros.h>
00041 #include <geometry_msgs/Pose2D.h>
00042 #include <std_msgs/Bool.h>
00043 
00044 namespace gm=geometry_msgs;
00045 namespace cmap=costmap_2d;
00046 namespace blp=base_local_planner;
00047 using std::vector;
00048 using std::max;
00049 
00050 namespace stepback_and_steerturn_recovery
00051 {
00052 
00055 class StepBackAndSteerTurnRecovery : public nav_core::RecoveryBehavior
00056 {
00057 public:
00058   
00060   StepBackAndSteerTurnRecovery();
00061 
00062   ~StepBackAndSteerTurnRecovery();
00063 
00065   void initialize (std::string n, tf::TransformListener* tf,
00066                    costmap_2d::Costmap2DROS* global_costmap,
00067                    costmap_2d::Costmap2DROS* local_costmap);
00068 
00070   void runBehavior();
00071 
00072 private:
00073   enum COSTMAP_SEARCH_MODE
00074   {
00075     FORWARD,
00076     FORWARD_LEFT,
00077     FORWARD_RIGHT,
00078     BACKWARD
00079   };
00080 
00081   enum TURN_DIRECTION
00082   {
00083     LEFT,
00084     RIGHT,
00085   };
00086 
00087   enum TURN_NO
00088   {
00089     FIRST_TURN = 0,
00090     SECOND_TURN = 1,
00091   };
00092   static const int CNT_TURN = 2;
00093 
00094   gm::Twist TWIST_STOP;
00095 
00096   gm::Pose2D getCurrentLocalPose () const;
00097   gm::Twist scaleGivenAccelerationLimits (const gm::Twist& twist, const double time_remaining) const;
00098   gm::Pose2D getPoseToObstacle (const gm::Pose2D& current, const gm::Twist& twist) const;
00099   double normalizedPoseCost (const gm::Pose2D& pose) const;
00100   gm::Twist transformTwist (const gm::Pose2D& pose) const;
00101   void moveSpacifiedLength (const gm::Twist twist, const double length, const COSTMAP_SEARCH_MODE mode = FORWARD) const;
00102   double getCurrentDiff(const gm::Pose2D initialPose, const COSTMAP_SEARCH_MODE mode = FORWARD) const;
00103   double getCurrentDistDiff(const gm::Pose2D initialPose, const double distination, const COSTMAP_SEARCH_MODE mode = FORWARD) const;
00104   double getMinimalDistanceToObstacle(const COSTMAP_SEARCH_MODE mode) const;
00105   int determineTurnDirection();
00106   double getDistBetweenTwoPoints(const gm::Pose2D pose1, const gm::Pose2D pose2) const;
00107 
00108 
00109   ros::NodeHandle nh_;
00110   costmap_2d::Costmap2DROS* global_costmap_;
00111   costmap_2d::Costmap2DROS* local_costmap_;
00112   costmap_2d::Costmap2D costmap_; // Copy of local_costmap_, used by world model
00113   std::string name_;
00114   tf::TransformListener* tf_;
00115   ros::Publisher cmd_vel_pub_;
00116   ros::Publisher recover_run_pub_;
00117   bool initialized_;
00118 
00119   // Memory owned by this object
00120   // Mutable because footprintCost is not declared const
00121   mutable base_local_planner::CostmapModel* world_model_;
00122 
00123   gm::Twist base_frame_twist_;
00124   
00125   double duration_;
00126   double linear_speed_limit_;
00127   double angular_speed_limit_;
00128   double linear_acceleration_limit_;
00129   double angular_acceleration_limit_;
00130   double controller_frequency_;
00131   double simulation_frequency_;
00132   double simulation_inc_;
00133 
00134   bool only_single_steering_;
00135   int trial_times_;
00136   double obstacle_patience_;
00137   double obstacle_check_frequency_;
00138   double sim_angle_resolution_;
00139   //-- back
00140   double linear_vel_back_;
00141   double step_back_length_;
00142   double step_back_timeout_;
00143   //-- steer
00144   double linear_vel_steer_;
00145   double angular_speed_steer_;
00146   double turn_angle_;
00147   double steering_timeout_;
00148   //-- forward
00149   double linear_vel_forward_;
00150   double step_forward_length_;
00151   double step_forward_timeout_;
00152 
00153 };
00154 
00155 } // namespace stepback_and_steerturn_recovery
00156 
00157 #endif // include guard


stepback_and_steerturn_recovery
Author(s): CIR-KIT , Masaru Morita
autogenerated on Sat Jun 8 2019 19:20:28