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
00042 #ifndef COSTMAP_TRAJECTORY_CHECKER_H_
00043 #define COSTMAP_TRAJECTORY_CHECKER_H_
00044
00045 #include <boost/thread.hpp>
00046
00047 #include <string>
00048
00049 #include <ros/ros.h>
00050 #include <costmap_2d/costmap_2d.h>
00051 #include <costmap_2d/costmap_2d_publisher.h>
00052 #include <costmap_2d/costmap_2d_ros.h>
00053 #include <base_local_planner/costmap_model.h>
00054 #include <geometry_msgs/Pose2D.h>
00055
00056
00064 class CostmapTrajectoryChecker {
00065 public:
00069 CostmapTrajectoryChecker();
00070
00078 CostmapTrajectoryChecker(costmap_2d::Costmap2DROS* costmap_ros,
00079 std::string frame_id,
00080 std::vector<geometry_msgs::Point> footprint,
00081 std::string topic = "");
00082
00088 CostmapTrajectoryChecker(costmap_2d::Costmap2DROS* costmap_ros, std::string topic = "");
00089
00091 CostmapTrajectoryChecker(const CostmapTrajectoryChecker &checker);
00092 CostmapTrajectoryChecker& operator=(const CostmapTrajectoryChecker& checker);
00093
00098 void initialize(costmap_2d::Costmap2DROS* costmap_ros, std::string topic = "");
00099
00100
00104 ~CostmapTrajectoryChecker();
00105
00110 void setFootprint(const std::vector<geometry_msgs::Point> &footprint);
00111
00119 void setFootprint(double length, double width, double x_offset, double y_offset);
00120
00122 std::vector<geometry_msgs::Point> getFootprint();
00123
00125 void setGlobalFrameID(std::string frame_id);
00126 void setRobotFrameID(std::string frame_id);
00127 std::string getGlobalFrameID();
00128 std::string getRobotFrameID();
00129
00131 void setPubTopic(std::string topic);
00132 std::string getPubTopic();
00133
00140 static void generateTrajectory(const geometry_msgs::Pose2D &start_pose,
00141 const geometry_msgs::Twist &vel, unsigned int num_steps, double dt,
00142 std::vector<geometry_msgs::Pose2D>& traj);
00143
00148 double checkTrajectory(const std::vector<geometry_msgs::Pose2D>& traj, bool update_map = false, bool clear_footprint = false);
00149
00154 double checkTrajectoryMonotonic(const std::vector<geometry_msgs::Pose2D>& traj, bool update_map = false, bool clear_footprint = false, unsigned int num_consec_points_in_collision = 5);
00155
00164 double checkTwist(const geometry_msgs::Twist &vel, unsigned int num_steps = 10, double dt = 0.2,
00165 bool update_map = false, bool clear_footprint = false);
00166
00175 double checkTwistMonotonic(const geometry_msgs::Twist &vel, unsigned int num_steps = 10, double dt = 0.2,
00176 bool update_map = false, bool clear_footprint = false);
00177
00178 bool clearFootprint(const geometry_msgs::Pose2D &traj, bool update_map);
00179
00180 bool clearFootprint(bool update_map);
00181
00182 private:
00183 tf::TransformListener tl_;
00184 base_local_planner::WorldModel* world_model_;
00185 costmap_2d::Costmap2DROS* costmap_ros_;
00186 costmap_2d::Costmap2D costmap_;
00187
00188 ros::NodeHandle nh_;
00189 ros::Publisher traj_pub_;
00190 std::string traj_topic_name_;
00191
00192 std::string robot_frame_;
00193 std::string global_frame_;
00194 double inscribed_radius_, circumscribed_radius_, inflation_radius_;
00195 std::vector<geometry_msgs::Point> footprint_spec_;
00196 bool initialized_;
00197
00205 double footprintCost(const geometry_msgs::Pose2D &pose);
00206
00212 bool getRobotPose(geometry_msgs::Pose2D &pose_2d) const;
00213
00214 void publishTrajectory(const std::vector<geometry_msgs::Pose2D>& path);
00215
00216 void getOrientedFootprint(const geometry_msgs::Pose2D &pose, std::vector<geometry_msgs::Point> &oriented_footprint);
00217
00224 static void poseTFToPose2D(const tf::Pose &pose_tf, geometry_msgs::Pose2D &pose_2d);
00225
00231 static void pose2DToTF(const geometry_msgs::Pose2D pose_2d, tf::Pose &pose_tf);
00232
00238 static void pose2DToPose(const geometry_msgs::Pose2D pose_2d, geometry_msgs::Pose &pose);
00239
00245 static void poseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose_2d);
00246
00253 static void integratePose(const geometry_msgs::Twist &vel, double dt,
00254 geometry_msgs::Pose2D &pose);
00255 };
00256
00257 #endif // COSTMAP_TRAJECTORY_CHECKER_H_