$search
00001 /* 00002 * safe_trajectory_planner.h 00003 * 00004 * Created on: Mar 25, 2010 00005 * Author: duhadway 00006 */ 00007 00008 #ifndef SAFE_TRAJECTORY_PLANNER_ROS_H_ 00009 #define SAFE_TRAJECTORY_PLANNER_ROS_H_ 00010 00011 #include <ros/ros.h> 00012 #include <costmap_2d/costmap_2d.h> 00013 #include <costmap_2d/costmap_2d_publisher.h> 00014 #include <costmap_2d/costmap_2d_ros.h> 00015 #include <base_local_planner/world_model.h> 00016 #include <base_local_planner/point_grid.h> 00017 #include <base_local_planner/costmap_model.h> 00018 #include <base_local_planner/voxel_grid_model.h> 00019 #include <safe_teleop_base/safe_trajectory_planner.h> 00020 00021 #include <tf/transform_datatypes.h> 00022 00023 #include <nav_msgs/Odometry.h> 00024 #include <geometry_msgs/PoseStamped.h> 00025 #include <geometry_msgs/Twist.h> 00026 #include <geometry_msgs/Point.h> 00027 00028 #include <tf/transform_listener.h> 00029 00030 #include <boost/thread.hpp> 00031 00032 #include <string> 00033 00034 #include <angles/angles.h> 00035 00036 #include <nav_core/base_local_planner.h> 00037 00038 00039 namespace safe_teleop { 00044 class SafeTrajectoryPlannerROS { 00045 public: 00052 SafeTrajectoryPlannerROS(tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros); 00053 00057 ~SafeTrajectoryPlannerROS(); 00058 00065 bool computeVelocityCommands(const geometry_msgs::Twist::ConstPtr& vel, geometry_msgs::Twist& cmd_vel); 00066 00067 private: 00072 bool stopped(); 00073 00081 double distance(double x1, double y1, double x2, double y2); 00082 00087 bool transformGlobalPlan(std::vector<geometry_msgs::PoseStamped>& transformed_plan); 00088 00092 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub, double r, double g, double b, double a); 00093 00094 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg); 00095 00096 void cmdCallback(const geometry_msgs::Twist::ConstPtr& vel); 00097 00098 std::vector<double> loadYVels(ros::NodeHandle node); 00099 00100 ros::NodeHandle nh_; 00101 00102 base_local_planner::WorldModel* world_model_; 00103 SafeTrajectoryPlanner* tc_; 00104 costmap_2d::Costmap2DROS* costmap_ros_; 00105 costmap_2d::Costmap2D costmap_; 00106 tf::TransformListener* tf_; 00107 std::string global_frame_; 00108 double max_sensor_range_; 00109 nav_msgs::Odometry base_odom_; 00110 std::string robot_base_frame_; 00111 double rot_stopped_velocity_, trans_stopped_velocity_; 00112 double inscribed_radius_, circumscribed_radius_, inflation_radius_; 00113 ros::Publisher l_plan_pub_; 00114 ros::Publisher u_plan_pub_; 00115 ros::Subscriber odom_sub_, user_sub_; 00116 00117 ros::Publisher cmd_pub_; 00118 ros::Subscriber cmd_sub_; 00119 00120 boost::recursive_mutex odom_lock_; 00121 double max_vel_th_, min_vel_th_; 00122 }; 00123 00124 } 00125 00126 00127 #endif /* SAFE_TRAJECTORY_PLANNER_ROS_H_ */