$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 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_