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 00039 #ifndef TWIST_RECOVERY_TWIST_RECOVERY_H 00040 #define TWIST_RECOVERY_TWIST_RECOVERY_H 00041 00042 #include <nav_core/recovery_behavior.h> 00043 #include <base_local_planner/costmap_model.h> 00044 #include <costmap_2d/costmap_2d_ros.h> 00045 #include <geometry_msgs/Pose2D.h> 00046 00047 namespace twist_recovery 00048 { 00049 00052 class TwistRecovery : public nav_core::RecoveryBehavior 00053 { 00054 public: 00055 00057 TwistRecovery(); 00058 00059 ~TwistRecovery(); 00060 00062 void initialize (std::string n, tf::TransformListener* tf, 00063 costmap_2d::Costmap2DROS* global_costmap, 00064 costmap_2d::Costmap2DROS* local_costmap); 00065 00067 void runBehavior(); 00068 00069 private: 00070 00071 geometry_msgs::Pose2D getCurrentLocalPose () const; 00072 geometry_msgs::Twist scaleGivenAccelerationLimits (const geometry_msgs::Twist& twist, const double time_remaining) const; 00073 double nonincreasingCostInterval (const geometry_msgs::Pose2D& current, const geometry_msgs::Twist& twist) const; 00074 double normalizedPoseCost (const geometry_msgs::Pose2D& pose) const; 00075 geometry_msgs::Twist transformTwist (const geometry_msgs::Pose2D& pose) const; 00076 00077 ros::NodeHandle nh_; 00078 costmap_2d::Costmap2DROS* global_costmap_; 00079 costmap_2d::Costmap2DROS* local_costmap_; 00080 std::string name_; 00081 tf::TransformListener* tf_; 00082 ros::Publisher pub_; 00083 bool initialized_; 00084 00085 // Memory owned by this object 00086 // Mutable because footprintCost is not declared const 00087 mutable base_local_planner::CostmapModel* world_model_; 00088 00089 geometry_msgs::Twist base_frame_twist_; 00090 00091 double duration_; 00092 double linear_speed_limit_; 00093 double angular_speed_limit_; 00094 double linear_acceleration_limit_; 00095 double angular_acceleration_limit_; 00096 double controller_frequency_; 00097 double simulation_inc_; 00098 00099 00100 }; 00101 00102 } // namespace twist_recovery 00103 00104 #endif // include guard