$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, 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 the Willow Garage 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 TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ 00038 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ 00039 00040 #include <ros/ros.h> 00041 #include <costmap_2d/costmap_2d.h> 00042 #include <costmap_2d/costmap_2d_publisher.h> 00043 #include <costmap_2d/costmap_2d_ros.h> 00044 #include <base_local_planner/world_model.h> 00045 #include <base_local_planner/point_grid.h> 00046 #include <base_local_planner/costmap_model.h> 00047 #include <base_local_planner/voxel_grid_model.h> 00048 #include <base_local_planner/trajectory_planner.h> 00049 #include <base_local_planner/map_grid_visualizer.h> 00050 00051 #include <base_local_planner/planar_laser_scan.h> 00052 00053 #include <tf/transform_datatypes.h> 00054 00055 #include <nav_msgs/Odometry.h> 00056 #include <geometry_msgs/PoseStamped.h> 00057 #include <geometry_msgs/Twist.h> 00058 #include <geometry_msgs/Point.h> 00059 00060 #include <tf/transform_listener.h> 00061 00062 #include <boost/thread.hpp> 00063 00064 #include <string> 00065 00066 #include <angles/angles.h> 00067 00068 #include <nav_core/base_local_planner.h> 00069 00070 #include <dynamic_reconfigure/server.h> 00071 #include <base_local_planner/BaseLocalPlannerConfig.h> 00072 00073 namespace base_local_planner { 00078 class TrajectoryPlannerROS : public nav_core::BaseLocalPlanner { 00079 public: 00083 TrajectoryPlannerROS(); 00084 00091 TrajectoryPlannerROS(std::string name, tf::TransformListener* tf, 00092 costmap_2d::Costmap2DROS* costmap_ros); 00093 00100 void initialize(std::string name, tf::TransformListener* tf, 00101 costmap_2d::Costmap2DROS* costmap_ros); 00102 00106 ~TrajectoryPlannerROS(); 00107 00113 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel); 00114 00120 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan); 00121 00126 bool isGoalReached(); 00127 00139 bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true); 00140 00152 double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true); 00153 00154 private: 00158 void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level); 00159 00168 bool rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel); 00169 00177 bool stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel); 00178 00179 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg); 00180 00181 std::vector<double> loadYVels(ros::NodeHandle node); 00182 00183 double sign(double x){ 00184 return x < 0.0 ? -1.0 : 1.0; 00185 } 00186 00187 WorldModel* world_model_; 00188 TrajectoryPlanner* tc_; 00189 costmap_2d::Costmap2DROS* costmap_ros_; 00190 costmap_2d::Costmap2D costmap_; 00191 MapGridVisualizer map_viz_; 00192 tf::TransformListener* tf_; 00193 std::string global_frame_; 00194 double max_sensor_range_; 00195 nav_msgs::Odometry base_odom_; 00196 std::string robot_base_frame_; 00197 double rot_stopped_velocity_, trans_stopped_velocity_; 00198 double xy_goal_tolerance_, yaw_goal_tolerance_, min_in_place_vel_th_; 00199 double inflation_radius_; 00200 std::vector<geometry_msgs::PoseStamped> global_plan_; 00201 bool prune_plan_; 00202 ros::Publisher g_plan_pub_, l_plan_pub_; 00203 ros::Subscriber odom_sub_; 00204 boost::recursive_mutex odom_lock_; 00205 bool initialized_; 00206 double max_vel_th_, min_vel_th_; 00207 double acc_lim_x_, acc_lim_y_, acc_lim_theta_; 00208 double sim_period_; 00209 bool rotating_to_goal_; 00210 bool latch_xy_goal_tolerance_, xy_tolerance_latch_; 00211 dynamic_reconfigure::Server<BaseLocalPlannerConfig> *dsrv_; 00212 base_local_planner::BaseLocalPlannerConfig default_config_; 00213 bool setup_; 00214 }; 00215 00216 }; 00217 00218 #endif