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 #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 <world_model.h>
00045 #include <point_grid.h>
00046 #include <costmap_model.h>
00047 #include <voxel_grid_model.h>
00048 #include <trajectory_planner.h>
00049 #include <map_grid_visualizer.h>
00050 
00051 #include <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 <iri_ackermann_local_planner/AckermannLocalPlannerConfig.h>
00072 
00073 namespace iri_ackermann_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(AckermannLocalPlannerConfig &config, uint32_t level);
00159 
00167       void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00168 
00169       double sign(double x){
00170         return x < 0.0 ? -1.0 : 1.0;
00171       }
00172 
00173       WorldModel* world_model_; 
00174       TrajectoryPlanner* tc_; 
00175       costmap_2d::Costmap2DROS* costmap_ros_; 
00176       costmap_2d::Costmap2D costmap_; 
00177       MapGridVisualizer map_viz_; 
00178       tf::TransformListener* tf_; 
00179       std::string global_frame_; 
00180       double max_sensor_range_; 
00181       nav_msgs::Odometry base_odom_; 
00182       std::string robot_base_frame_; 
00183       double rot_stopped_velocity_, trans_stopped_velocity_;
00184       double xy_goal_tolerance_, yaw_goal_tolerance_;
00185       double inflation_radius_; 
00186       std::vector<geometry_msgs::PoseStamped> global_plan_;
00187       bool prune_plan_;
00188       ros::Publisher g_plan_pub_, l_plan_pub_;
00189       ros::Subscriber odom_sub_;
00190       boost::recursive_mutex odom_lock_;
00191       bool initialized_;
00192       bool rotating_to_goal_;
00193       bool latch_xy_goal_tolerance_, xy_tolerance_latch_;
00194       dynamic_reconfigure::Server<AckermannLocalPlannerConfig> *dsrv_;
00195       iri_ackermann_local_planner::AckermannLocalPlannerConfig default_config_;
00196       bool setup_;
00197       
00198       std::vector < std::vector < geometry_msgs::PoseStamped > > subPathList;
00199       std::vector < geometry_msgs::PoseStamped > subPath;
00200       unsigned int subPathIndex;
00201 
00202       geometry_msgs::Twist ackermann_state_;
00203   };
00204 
00205 };
00206 
00207 #endif