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 <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 namespace base_local_planner {
00075 class TrajectoryPlannerROS : public nav_core::BaseLocalPlanner {
00076 public:
00080 TrajectoryPlannerROS();
00081
00088 TrajectoryPlannerROS(std::string name, tf::TransformListener* tf,
00089 costmap_2d::Costmap2DROS* costmap_ros);
00090
00097 void initialize(std::string name, tf::TransformListener* tf,
00098 costmap_2d::Costmap2DROS* costmap_ros);
00099
00103 ~TrajectoryPlannerROS();
00104
00110 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00111
00117 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00118
00123 bool isGoalReached();
00124
00136 bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true);
00137
00149 double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true);
00150
00151 private:
00160 bool rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel);
00161
00169 bool stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel);
00170
00171 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00172
00173 std::vector<double> loadYVels(ros::NodeHandle node);
00174
00175 double sign(double x){
00176 return x < 0.0 ? -1.0 : 1.0;
00177 }
00178
00179 WorldModel* world_model_;
00180 TrajectoryPlanner* tc_;
00181 costmap_2d::Costmap2DROS* costmap_ros_;
00182 costmap_2d::Costmap2D costmap_;
00183 MapGridVisualizer map_viz_;
00184 tf::TransformListener* tf_;
00185 std::string global_frame_;
00186 double max_sensor_range_;
00187 nav_msgs::Odometry base_odom_;
00188 std::string robot_base_frame_;
00189 double rot_stopped_velocity_, trans_stopped_velocity_;
00190 double xy_goal_tolerance_, yaw_goal_tolerance_, min_in_place_vel_th_;
00191 double inscribed_radius_, circumscribed_radius_, inflation_radius_;
00192 std::vector<geometry_msgs::PoseStamped> global_plan_;
00193 bool prune_plan_;
00194 ros::Publisher g_plan_pub_, l_plan_pub_;
00195 ros::Subscriber odom_sub_;
00196 boost::recursive_mutex odom_lock_;
00197 bool initialized_;
00198 double max_vel_th_, min_vel_th_;
00199 double acc_lim_x_, acc_lim_y_, acc_lim_theta_;
00200 double sim_period_;
00201 bool rotating_to_goal_;
00202 bool latch_xy_goal_tolerance_, xy_tolerance_latch_;
00203 };
00204
00205 };
00206
00207 #endif