pose_follower.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2009, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #ifndef POSE_FOLLOWER_POSE_FOLLOWER_H_
00038 #define POSE_FOLLOWER_POSE_FOLLOWER_H_
00039 #include <ros/ros.h>
00040 #include <tf/tf.h>
00041 #include <tf/transform_datatypes.h>
00042 #include <tf/transform_listener.h>
00043 #include <nav_core/base_local_planner.h>
00044 #include <costmap_2d/costmap_2d_ros.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <geometry_msgs/Twist.h>
00047 #include <nav_msgs/Odometry.h>
00048 #include <base_local_planner/trajectory_planner_ros.h>
00049 
00050 namespace pose_follower {
00051   class PoseFollower : public nav_core::BaseLocalPlanner {
00052     public:
00053       PoseFollower();
00054       void initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
00055       bool isGoalReached();
00056       bool setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan);
00057       bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00058 
00059     private:
00060       inline double sign(double n){
00061         return n < 0.0 ? -1.0 : 1.0;
00062       }
00063 
00064       geometry_msgs::Twist diff2D(const tf::Pose& pose1, const tf::Pose&  pose2);
00065       geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist);
00066       double headingDiff(double pt_x, double pt_y, double x, double y, double heading);
00067 
00068       bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, 
00069           const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
00070           std::vector<geometry_msgs::PoseStamped>& transformed_plan);
00071 
00072       void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00073       bool stopped();
00074       void publishPlan(const std::vector<geometry_msgs::PoseStamped> &path, const ros::Publisher &pub);
00075 
00076       tf::TransformListener* tf_;
00077       costmap_2d::Costmap2DROS* costmap_ros_;
00078       ros::Publisher vel_pub_;
00079       ros::Publisher global_plan_pub_;
00080       double K_trans_, K_rot_, tolerance_trans_, tolerance_rot_;
00081       double tolerance_timeout_;
00082       double max_vel_lin_, max_vel_th_;
00083       double min_vel_lin_, min_vel_th_;
00084       double min_in_place_vel_th_, in_place_trans_vel_;
00085       bool allow_backwards_;
00086       bool turn_in_place_first_;
00087       double max_heading_diff_before_moving_;
00088       bool holonomic_;
00089       boost::mutex odom_lock_;
00090       ros::Subscriber odom_sub_;
00091       nav_msgs::Odometry base_odom_;
00092       double trans_stopped_velocity_, rot_stopped_velocity_;
00093       ros::Time goal_reached_time_;
00094       unsigned int current_waypoint_; 
00095       std::vector<geometry_msgs::PoseStamped> global_plan_;
00096       base_local_planner::TrajectoryPlannerROS collision_planner_;
00097       int samples_;
00098   };
00099 };
00100 #endif


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Thu Mar 28 2019 03:37:40