$search
00001 //================================================================================================= 00002 // Copyright (c) 2011, Stefan Kohlbrecher, Johannes Meyer TU Darmstadt 00003 // All rights reserved. 00004 00005 // Redistribution and use in source and binary forms, with or without 00006 // modification, are permitted provided that the following conditions are met: 00007 // * Redistributions of source code must retain the above copyright 00008 // notice, this list of conditions and the following disclaimer. 00009 // * Redistributions in binary form must reproduce the above copyright 00010 // notice, this list of conditions and the following disclaimer in the 00011 // documentation and/or other materials provided with the distribution. 00012 // * Neither the name of the Simulation, Systems Optimization and Robotics 00013 // group, TU Darmstadt nor the names of its contributors may be used to 00014 // endorse or promote products derived from this software without 00015 // specific prior written permission. 00016 00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY 00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00027 //================================================================================================= 00028 00029 #include <stdio.h> 00030 #include <stdlib.h> 00031 //#include <libgen.h> 00032 //#include <fstream> 00033 00034 #include "ros/ros.h" 00035 #include "ros/console.h" 00036 #include "nav_msgs/MapMetaData.h" 00037 #include "nav_msgs/OccupancyGrid.h" 00038 00039 #include <boost/thread.hpp> 00040 00041 #include <tf/transform_listener.h> 00042 00043 #include "nav_msgs/GetMap.h" 00044 00045 #include "hector_marker_drawing/HectorDrawings.h" 00046 #include "hector_map_tools/HectorMapTools.h" 00047 00048 #include "hector_nav_msgs/GetDistanceToObstacle.h" 00049 #include "hector_nav_msgs/GetSearchPosition.h" 00050 00051 00052 class OccupancyGridContainer 00053 { 00054 public: 00055 OccupancyGridContainer(std::string sub_topic, std::string prefix, ros::NodeHandle& nh, HectorDrawings* drawing_provider, tf::TransformListener* tf_) 00056 : drawing_provider_(drawing_provider) 00057 , tf_(tf_) 00058 { 00059 00060 std::string service_name = "map"; 00061 map_service_ = nh.advertiseService(service_name, &OccupancyGridContainer::mapServiceCallback, this); 00062 00063 std::string lookup_service_name = "get_distance_to_obstacle"; 00064 dist_lookup_service_ = nh.advertiseService(lookup_service_name, &OccupancyGridContainer::lookupServiceCallback, this); 00065 00066 std::string get_search_pos_service_name = "get_search_position"; 00067 get_search_pos_service_ = nh.advertiseService(get_search_pos_service_name, &OccupancyGridContainer::getSearchPosServiceCallback, this); 00068 00069 map_sub_ = nh.subscribe("map", 1, &OccupancyGridContainer::mapCallback, this); 00070 } 00071 00072 ~OccupancyGridContainer() 00073 {} 00074 00075 bool mapServiceCallback(nav_msgs::GetMap::Request &req, 00076 nav_msgs::GetMap::Response &res ) 00077 { 00078 ROS_INFO("hector_map_server map service called"); 00079 00080 if (!map_ptr_){ 00081 ROS_INFO("map_server has no map yet, no map service available"); 00082 return false; 00083 } 00084 00085 res.map = *map_ptr_; 00086 00087 return true; 00088 } 00089 00090 bool lookupServiceCallback(hector_nav_msgs::GetDistanceToObstacle::Request &req, 00091 hector_nav_msgs::GetDistanceToObstacle::Response &res ) 00092 { 00093 //ROS_INFO("hector_map_server lookup service called"); 00094 00095 00096 if (!map_ptr_){ 00097 ROS_INFO("map_server has no map yet, no lookup service available"); 00098 return false; 00099 } 00100 00101 tf::StampedTransform stamped_pose; 00102 00103 00104 00105 try{ 00106 tf_->waitForTransform(map_ptr_->header.frame_id,req.point.header.frame_id, req.point.header.stamp, ros::Duration(1.0)); 00107 tf_->lookupTransform(map_ptr_->header.frame_id, req.point.header.frame_id, req.point.header.stamp, stamped_pose); 00108 00109 tf::Point v2_tf; 00110 tf::pointMsgToTF(req.point.point,v2_tf); 00111 00112 tf::Vector3 v1 = stamped_pose * tf::Vector3(0.0, 0.0, 0.0); 00113 tf::Vector3 v2 = stamped_pose * v2_tf; 00114 tf::Vector3 diff = v2 - v1; 00115 v2 = v1 + diff / tf::Vector3(diff.x(), diff.y(), 0.0).length() * 5.0f; 00116 00117 Eigen::Vector2f start(v1.x(),v1.y()); 00118 Eigen::Vector2f end(v2.x(),v2.y()); 00119 00120 Eigen::Vector2f hit_world; 00121 //float dist = dist_meas_.getDist(start,end, &hit_world); 00122 float dist = dist_meas_.getDist(start,end,&hit_world); 00123 00124 if (dist >=0.0f){ 00125 tf::Vector3 diff (v2-v1); 00126 00127 float angle = diff.angle(tf::Vector3(diff.x(),diff.y(),0.0f)); 00128 00129 res.distance = dist/cos(angle); 00130 00131 }else{ 00132 res.distance = -1.0f; 00133 } 00134 00135 //debug drawing 00136 if (false){ 00137 00138 float cube_scale = map_ptr_->info.resolution; 00139 drawing_provider_->setColor(1.0, 0.0, 0.0); 00140 drawing_provider_->setScale(static_cast<double>(cube_scale)); 00141 00142 drawing_provider_->drawPoint(start); 00143 00144 drawing_provider_->setColor(0.0, 1.0, 0.0); 00145 drawing_provider_->drawPoint(end); 00146 00147 if (dist >= 0.0f){ 00148 drawing_provider_->setColor(0.0, 0.0, 1.0); 00149 drawing_provider_->drawPoint(hit_world); 00150 } 00151 00152 drawing_provider_->sendAndResetData(); 00153 } 00154 00155 return true; 00156 00157 } 00158 catch(tf::TransformException e) 00159 { 00160 ROS_ERROR("Transform failed in lookup distance service call: %s",e.what()); 00161 } 00162 00163 return false; 00164 } 00165 00166 bool getSearchPosServiceCallback(hector_nav_msgs::GetSearchPosition::Request &req, 00167 hector_nav_msgs::GetSearchPosition::Response &res ) 00168 { 00169 if (!map_ptr_){ 00170 ROS_INFO("map_server has no map yet, no get best search pos service available"); 00171 return false; 00172 } 00173 00174 try{ 00175 00176 tf::Stamped<tf::Pose> ooi_pose, transformed_pose, search_position; 00177 tf::poseStampedMsgToTF(req.ooi_pose, ooi_pose); 00178 00179 tf_->waitForTransform(map_ptr_->header.frame_id, req.ooi_pose.header.frame_id, req.ooi_pose.header.stamp, ros::Duration(1.0)); 00180 tf_->transformPose(map_ptr_->header.frame_id, ooi_pose, transformed_pose); 00181 00182 tf::Vector3 direction(-req.distance, 0.0, 0.0); 00183 search_position = transformed_pose; 00184 search_position.setOrigin(transformed_pose.getOrigin() + transformed_pose.getBasis() * direction); 00185 00186 tf::poseStampedTFToMsg(search_position, res.search_pose); 00187 00188 return true; 00189 00190 // //tf::Point v2_tf; 00191 // //tf::pointMsgToTF(req.point.point,v2_tf); 00192 00193 // tf::Vector3 v1 = stamped_pose * tf::Vector3(0.0, 0.0, 0.0); 00194 00195 // //warning: 3D! 00196 // tf::Vector3 v2 = stamped_pose * tf::Vector3(-1.0, 0.0, 0.0); 00197 00198 // tf::Vector3 dir = v2-v1; 00199 00200 // Eigen::Vector2f dir_2d (dir.x(), dir.y()); 00201 00202 // dir_2d.normalize(); 00203 00204 // Eigen::Vector2f searchPos (Eigen::Vector2f(v1.x(),v1.y()) + (dir_2d*0.5f)); 00205 00206 // //copy original pose message but set translation 00207 // res.search_pose.pose = ooi_pose.pose; 00208 00209 // res.search_pose.pose.position.x = searchPos.x(); 00210 // res.search_pose.pose.position.y = searchPos.y(); 00211 00212 //return true; 00213 00214 00215 //Eigen::Vector2f ooi_pos(v1.x(),v1.y()); 00216 //Eigen::Vector2f sample_point_pos(v2.x(),v2.y()); 00217 00218 00219 //float dist_from_target = dist_meas_.getDist(ooi_pos,sample_point_pos); 00220 //float dist_from_sample_point = dist_meas_.getDist(sample_point_pos, ooi_pos); 00221 00222 00223 00224 /* 00225 if (dist >=0.0f){ 00226 tf::Vector3 diff (v2-v1); 00227 00228 float angle = diff.angle(tf::Vector3(diff.x(),diff.y(),0.0f)); 00229 00230 res.distance = dist/cos(angle); 00231 00232 00233 //debug drawing 00234 if (true){ 00235 00236 float cube_scale = map_ptr_->info.resolution; 00237 drawing_provider_->setColor(1.0, 0.0, 0.0); 00238 drawing_provider_->setScale(static_cast<double>(cube_scale)); 00239 00240 drawing_provider_->drawPoint(start); 00241 drawing_provider_->drawPoint(end); 00242 00243 if (dist >= 0.0f){ 00244 drawing_provider_->setColor(0.0, 0.0, 1.0); 00245 drawing_provider_->drawPoint(hit_world); 00246 } 00247 00248 drawing_provider_->sendAndResetData(); 00249 } 00250 00251 } 00252 */ 00253 //return true; 00254 00255 } catch(tf::TransformException e){ 00256 ROS_ERROR("Transform failed in getSearchPosition service call: %s",e.what()); 00257 } 00258 00259 return false; 00260 } 00261 00262 void mapCallback(const nav_msgs::OccupancyGridConstPtr& map) 00263 { 00264 map_ptr_ = map; 00265 00266 dist_meas_.setMap(map_ptr_); 00267 } 00268 00269 //Services 00270 ros::ServiceServer map_service_; 00271 ros::ServiceServer dist_lookup_service_; 00272 ros::ServiceServer get_search_pos_service_; 00273 00274 //Subscriber 00275 ros::Subscriber map_sub_; 00276 00277 HectorMapTools::DistanceMeasurementProvider dist_meas_; 00278 00279 HectorDrawings* drawing_provider_; 00280 tf::TransformListener* tf_; 00281 00282 //nav_msgs::MapMetaData meta_data_message_; 00283 nav_msgs::GetMap::Response map_resp_; 00284 00285 nav_msgs::OccupancyGridConstPtr map_ptr_; 00286 }; 00287 00288 class HectorMapServer 00289 { 00290 public: 00292 HectorMapServer(ros::NodeHandle& private_nh) 00293 { 00294 std::string frame_id; 00295 00296 hector_drawings_ = new HectorDrawings(); 00297 hector_drawings_->setNamespace("map_server"); 00298 00299 mapContainer = new OccupancyGridContainer("map", "" ,private_nh, hector_drawings_,&tf_); 00300 } 00301 00302 ~HectorMapServer() 00303 { 00304 delete mapContainer; 00305 00306 00307 delete hector_drawings_; 00308 } 00309 00310 00311 public: 00312 OccupancyGridContainer* mapContainer; 00313 private: 00314 00315 HectorDrawings* hector_drawings_; 00316 tf::TransformListener tf_; 00317 }; 00318 00319 int main(int argc, char **argv) 00320 { 00321 ros::init(argc, argv, "hector_map_server"); 00322 ros::NodeHandle nh; 00323 00324 HectorMapServer ms(nh); 00325 00326 ros::spin(); 00327 00328 return 0; 00329 } 00330