$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2008, Willow Garage, Inc. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Willow Garage nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 * Author: Eitan Marder-Eppstein 00036 *********************************************************************/ 00037 #ifndef COSTMAP_COSTMAP_2D_ROS_H_ 00038 #define COSTMAP_COSTMAP_2D_ROS_H_ 00039 00040 #include <XmlRpc.h> 00041 #include <ros/ros.h> 00042 #include <ros/console.h> 00043 #include <costmap_2d/costmap_2d.h> 00044 #include <costmap_2d/costmap_2d_publisher.h> 00045 #include <costmap_2d/observation_buffer.h> 00046 #include <costmap_2d/voxel_costmap_2d.h> 00047 #include <costmap_2d/VoxelGrid.h> 00048 #include <nav_msgs/OccupancyGrid.h> 00049 #include <map> 00050 #include <vector> 00051 #include <string> 00052 #include <sstream> 00053 #include <boost/tokenizer.hpp> 00054 #include <boost/foreach.hpp> 00055 #include <boost/algorithm/string.hpp> 00056 00057 #include <tf/transform_datatypes.h> 00058 00059 #include <tf/message_filter.h> 00060 #include <message_filters/subscriber.h> 00061 00062 #include <tf/transform_listener.h> 00063 00064 #include <sensor_msgs/LaserScan.h> 00065 #include <laser_geometry/laser_geometry.h> 00066 00067 #include <sensor_msgs/PointCloud.h> 00068 00069 //Support for PointCloud2 messages 00070 #include <sensor_msgs/PointCloud2.h> 00071 00072 // Thread suppport 00073 #include <boost/thread.hpp> 00074 #include <boost/shared_ptr.hpp> 00075 00076 #include <stdlib.h> 00077 #include <dynamic_reconfigure/server.h> 00078 #include <costmap_2d/Costmap2DConfig.h> 00079 00080 namespace costmap_2d { 00081 00088 class Costmap2DROS { 00089 public: 00095 Costmap2DROS(std::string name, tf::TransformListener& tf); 00096 00100 ~Costmap2DROS(); 00101 00108 void addObservationBuffer(const boost::shared_ptr<ObservationBuffer>& buffer); 00109 00115 bool getMarkingObservations(std::vector<Observation>& marking_observations) const; 00116 00122 bool getClearingObservations(std::vector<Observation>& clearing_observations) const; 00123 00128 void updateMap(); 00129 00137 void getOrientedFootprint(double x, double y, double theta, std::vector<geometry_msgs::Point>& oriented_footprint) const; 00138 00143 void getOrientedFootprint(std::vector<geometry_msgs::Point>& oriented_footprint) const; 00144 00150 bool getRobotPose(tf::Stamped<tf::Pose>& global_pose) const; 00151 00155 void clearRobotFootprint(); 00156 00161 void clearRobotFootprint(const tf::Stamped<tf::Pose>& global_pose); 00162 00169 bool setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value); 00170 00176 void resetMapOutsideWindow(double size_x, double size_y); 00177 00183 void clearNonLethalWindow(double size_x, double size_y); 00184 00189 void getCostmapCopy(Costmap2D& costmap) const; 00190 00197 void updateStaticMap(const nav_msgs::OccupancyGrid& new_map); 00198 00207 void getCostmapWindowCopy(double win_size_x, double win_size_y, Costmap2D& costmap) const; 00208 00219 void getCostmapWindowCopy(double win_center_x, double win_center_y, double win_size_x, double win_size_y, Costmap2D& costmap) const; 00220 00225 unsigned int getSizeInCellsX() const; 00226 00231 unsigned int getSizeInCellsY() const; 00232 00237 double getResolution() const; 00238 00243 std::string getGlobalFrameID() const; 00244 00249 std::string getBaseFrameID() const; 00250 00255 double getInscribedRadius() const; 00256 00261 double getCircumscribedRadius() const; 00262 00267 double getInflationRadius() const; 00268 00273 std::vector<geometry_msgs::Point> getRobotFootprint() const; 00274 00279 bool isCurrent() {return current_;} 00280 00286 void start(); 00287 00291 void stop(); 00292 00293 00297 void pause() { 00298 stop_updates_ = true; 00299 initialized_ = false; 00300 } 00301 00302 00306 void resume(){ 00307 stop_updates_ = false; 00308 00309 //block until the costmap is re-initialized.. meaning one update cycle has run 00310 ros::Rate r(100.0); 00311 while(!initialized_) 00312 r.sleep(); 00313 } 00314 00315 private: 00319 void reconfigureCB(costmap_2d::Costmap2DConfig &config, uint32_t level); 00320 00321 void movementCB(const ros::TimerEvent &event); 00322 00329 void incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map); 00330 00335 void initFromMap(const nav_msgs::OccupancyGrid& map); 00336 00342 void laserScanCallback(const sensor_msgs::LaserScanConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer); 00343 00349 void pointCloudCallback(const sensor_msgs::PointCloudConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer); 00350 00356 void pointCloud2Callback(const sensor_msgs::PointCloud2ConstPtr& message, const boost::shared_ptr<ObservationBuffer>& buffer); 00357 00362 void mapUpdateLoop(double frequency); 00363 00367 std::vector<geometry_msgs::Point> loadRobotFootprint(ros::NodeHandle node, double inscribed_radius, double circumscribed_radius); 00368 00372 double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1); 00373 00374 inline double distance(double x0, double y0, double x1, double y1){ 00375 return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0)); 00376 } 00377 00378 std::string name_; 00379 tf::TransformListener& tf_; 00380 laser_geometry::LaserProjection projector_; 00381 Costmap2D* costmap_; 00382 std::string global_frame_; 00383 std::string robot_base_frame_; 00384 boost::thread* map_update_thread_; 00385 00386 std::vector<boost::shared_ptr<tf::MessageFilterBase> > observation_notifiers_; 00387 std::vector<boost::shared_ptr<message_filters::SubscriberBase> > observation_subscribers_; 00388 std::vector<boost::shared_ptr<ObservationBuffer> > observation_buffers_; 00389 std::vector<boost::shared_ptr<ObservationBuffer> > marking_buffers_; 00390 std::vector<boost::shared_ptr<ObservationBuffer> > clearing_buffers_; 00391 bool rolling_window_; 00392 bool current_; 00393 double transform_tolerance_; // timeout before transform errors 00394 Costmap2DPublisher* costmap_publisher_; 00395 bool stop_updates_, initialized_, stopped_; 00396 bool publish_voxel_; 00397 std::vector<geometry_msgs::Point> footprint_spec_; 00398 ros::Publisher voxel_pub_; 00399 mutable boost::recursive_mutex lock_; 00400 bool map_update_thread_shutdown_; 00401 bool save_debug_pgm_; 00402 ros::Subscriber map_sub_; 00403 bool map_initialized_; 00404 std::string tf_prefix_; 00405 00406 //we need this to be able to initialize the map using a latched topic approach 00407 //strictly speaking, we don't need the lock, but since this all happens on startup 00408 //and there is little overhead... we'll be careful and use it anyways just in case 00409 //the compiler or scheduler does something weird with the code 00410 boost::recursive_mutex map_data_lock_; 00411 nav_msgs::MapMetaData map_meta_data_; 00412 std::vector<unsigned char> input_data_; 00413 bool costmap_initialized_; 00414 00415 bool robot_stopped_, setup_, static_map_; 00416 00417 dynamic_reconfigure::Server<costmap_2d::Costmap2DConfig> *dsrv_; 00418 boost::mutex map_update_mutex_; 00419 boost::recursive_mutex configuration_mutex_; 00420 costmap_2d::Costmap2DConfig last_config_; 00421 costmap_2d::Costmap2DConfig maptype_config_; 00422 costmap_2d::Costmap2DConfig default_config_; 00423 ros::Timer timer_; 00424 tf::Stamped<tf::Pose> old_pose_; 00425 }; 00426 }; 00427 00428 #endif 00429