$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 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 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 */ 00030 00039 #include <occupancy_grid_utils/geometry.h> 00040 #include <occupancy_grid_utils/shortest_path.h> 00041 #include <ros/ros.h> 00042 #include <actionlib/client/simple_action_client.h> 00043 #include <move_base_msgs/MoveBaseAction.h> 00044 #include <visualization_msgs/Marker.h> 00045 #include <tf/transform_listener.h> 00046 #include <boost/foreach.hpp> 00047 #include <boost/math/constants/constants.hpp> 00048 #include <geometry_msgs/PolygonStamped.h> 00049 00050 namespace semanticmodel 00051 { 00052 namespace gu=occupancy_grid_utils; 00053 namespace nm=nav_msgs; 00054 namespace vm=visualization_msgs; 00055 namespace gm=geometry_msgs; 00056 namespace al=actionlib; 00057 namespace mbm=move_base_msgs; 00058 00059 using std::set; 00060 using std::vector; 00061 using boost::optional; 00062 using std::cerr; 00063 using std::endl; 00064 00065 typedef boost::mutex::scoped_lock Lock; 00066 typedef std::set<gu::Cell> Cells; 00067 00068 00069 class Node 00070 { 00071 public: 00072 00073 Node (); 00074 00075 // Store map 00076 void mapCB (const nm::OccupancyGrid& map); 00077 00078 // Overall main function that goes through waypoints 00079 void run (); 00080 00081 // Publish visualization 00082 void visualize(const ros::WallTimerEvent& e); 00083 00084 // Update which targets are seen given current pose 00085 void updateSeen(const ros::TimerEvent&e = ros::TimerEvent()); 00086 00087 private: 00088 00089 gm::Pose getCurrentPose (); 00090 00091 gm::Polygon getVisibleRegion (const gm::Pose& p) const; 00092 00093 optional<size_t> getNextGoal(); 00094 00095 bool navigateWaypoint (size_t i); 00096 00097 optional<size_t> getViewpoint(size_t target); 00098 00099 ros::NodeHandle nh_; 00100 boost::mutex mutex_; 00101 00102 const float robot_radius_; 00103 00104 // Map of the environment 00105 boost::optional<nm::OccupancyGrid> map_; 00106 00107 // Points we want to try to look at 00108 vector<gu::Cell> targets_; 00109 00110 // Which targets have and haven't been seen yet 00111 set<size_t> seen_, unseen_; 00112 00113 // Potential places to look from 00114 vector<gm::Pose> view_poses_; 00115 00116 // Precomputation of which targets are visible from where 00117 vector<vector<bool> > is_visible_; 00118 00119 // Which view poses are forbidden, either because we've been 00120 // there before, or they're not reachable 00121 set<size_t> forbidden_; 00122 00123 // Flag for node state being initialized 00124 bool initialized_; 00125 00126 00127 al::SimpleActionClient<mbm::MoveBaseAction> mb_client_; 00128 ros::Publisher vis_pub_; 00129 ros::Publisher visible_poly_pub_; 00130 ros::Subscriber map_sub_; 00131 ros::WallTimer vis_timer_; 00132 ros::Timer update_timer_; 00133 tf::TransformListener tf_; 00134 }; 00135 00136 Node::Node () : 00137 robot_radius_(0.7), mb_client_("move_base", true), 00138 vis_pub_(nh_.advertise<vm::Marker>("visualization_marker", 100)), 00139 visible_poly_pub_(nh_.advertise<gm::PolygonStamped>("visible_polygon", 100)), 00140 map_sub_(nh_.subscribe("/map", 10, &Node::mapCB, this)), 00141 vis_timer_(nh_.createWallTimer(ros::WallDuration(1.0), &Node::visualize, 00142 this)), 00143 update_timer_(nh_.createTimer(ros::Duration(0.3), &Node::updateSeen, this)) 00144 {} 00145 00146 00147 void Node::mapCB (const nm::OccupancyGrid& map) 00148 { 00149 Lock l(mutex_); 00150 map_ = map; 00151 ROS_INFO ("Map received"); 00152 } 00153 00154 // Functor used to discretize reachable subset of grid 00155 struct CheckReachable 00156 { 00157 CheckReachable (const nm::MapMetaData& info, gu::ResultPtr navfn, 00158 float max_dist) : 00159 info(info), navfn(navfn), max_dist(max_dist) 00160 {} 00161 00162 bool operator() (const gu::Cell& c) const 00163 { 00164 boost::optional<double> dist = gu::distanceTo(navfn, c); 00165 return (dist && (*dist < max_dist)); 00166 } 00167 00168 nm::MapMetaData info; 00169 gu::ResultPtr navfn; 00170 float max_dist; 00171 00172 }; 00173 00174 void Node::run () 00175 { 00176 // Wait for the map 00177 while (ros::ok()) 00178 { 00179 ros::WallDuration(1.0).sleep(); 00180 Lock l(mutex_); 00181 if (map_) 00182 break; 00183 ROS_INFO ("Waiting for map"); 00184 } 00185 ROS_INFO("Generating targets and viewpoints"); 00186 00187 // Get current pose 00188 const gm::Pose pose = getCurrentPose(); 00189 const gu::Cell current_cell = gu::pointCell(map_->info, pose.position); 00190 00191 // Get potential view positions: reachable cells that aren't too far away 00192 nm::OccupancyGrid::Ptr inflated = gu::inflateObstacles(*map_, robot_radius_); 00193 gu::ResultPtr nav = gu::singleSourceShortestPaths(*inflated, current_cell); 00194 Cells view_positions = gu::tileCells(map_->info, 0.5, 00195 CheckReachable(map_->info, nav, 7)); 00196 00197 // Get targets: reachable cells (in uninflated grid) that aren't too far away 00198 gu::ResultPtr nav2 = gu::singleSourceShortestPaths(*map_, current_cell); 00199 Cells target_set = gu::tileCells(map_->info, 0.3, 00200 CheckReachable(map_->info, nav2, 7)); 00201 00202 { 00203 // Acquire lock before modifying state 00204 Lock l(mutex_); 00205 targets_.insert(targets_.end(), target_set.begin(), target_set.end()); 00206 00207 // Initially all targets are unseen 00208 for (size_t i=0; i<targets_.size(); i++) 00209 unseen_.insert(i); 00210 00211 // For each view position, we consider a bunch of orientations 00212 const float pi = boost::math::constants::pi<float>(); 00213 BOOST_FOREACH (const gu::Cell& pos, view_positions) 00214 { 00215 for (float yaw=0; yaw < 2*pi; yaw+=pi/2) 00216 { 00217 gm::Pose view_pose; 00218 view_pose.position = cellCenter(map_->info, pos); 00219 view_pose.orientation = tf::createQuaternionMsgFromYaw(yaw); 00220 view_poses_.push_back(view_pose); 00221 } 00222 } 00223 00224 // Precompute visibility relation between viewpoints and targets 00225 ROS_INFO ("Computing visibility relation"); 00226 is_visible_.resize(view_poses_.size()); 00227 for (size_t i=0; i<view_poses_.size(); i++) 00228 { 00229 const gm::Polygon poly = getVisibleRegion(view_poses_[i]); 00230 is_visible_[i].resize(targets_.size()); 00231 Cells visible_positions = gu::cellsInConvexPolygon(map_->info, poly); 00232 for (size_t j=0; j<targets_.size(); j++) 00233 { 00234 if (visible_positions.find(targets_[j])!=visible_positions.end()) 00235 { 00236 is_visible_[i][j] = true; 00237 } 00238 } 00239 } 00240 00241 ROS_INFO ("Targets generated"); 00242 initialized_ = true; 00243 } 00244 00245 // Repeatedly pick a navigation waypoint, try to reach it 00246 // Stop when there's no valid waypoint any more 00247 while (ros::ok()) 00248 { 00249 boost::optional<size_t> next_goal; 00250 { 00251 Lock l(mutex_); 00252 next_goal = getNextGoal(); 00253 if (!next_goal) 00254 { 00255 ROS_INFO ("No more valid goals; terminating"); 00256 break; 00257 } 00258 } 00259 ROS_INFO ("Navigating to %zu", *next_goal); 00260 const bool success = navigateWaypoint(*next_goal); 00261 if (success) 00262 ROS_INFO("Navigation succeeded"); 00263 else 00264 ROS_INFO("Navigation failed"); 00265 forbidden_.insert(*next_goal); 00266 } 00267 } 00268 00269 00270 optional<size_t> Node::getViewpoint (const size_t target) 00271 { 00272 for (size_t i=0; i<view_poses_.size(); i++) 00273 { 00274 if (forbidden_.find(i)==forbidden_.end()) 00275 { 00276 if (is_visible_[i][target]) 00277 return i; 00278 } 00279 } 00280 return optional<size_t>(); 00281 } 00282 00283 optional<size_t> Node::getNextGoal () 00284 { 00285 optional<size_t> g; 00286 BOOST_FOREACH (const size_t target, unseen_) 00287 { 00288 // cerr << "Considering target " << target << endl; 00289 g = getViewpoint(target); 00290 if (g) 00291 break; 00292 } 00293 return g; 00294 } 00295 00296 bool Node::navigateWaypoint (const size_t wp) 00297 { 00298 mbm::MoveBaseGoal goal; 00299 goal.target_pose.header.frame_id = "/map"; 00300 goal.target_pose.header.stamp = ros::Time::now(); 00301 goal.target_pose.pose = view_poses_[wp]; 00302 00303 al::SimpleClientGoalState state = 00304 mb_client_.sendGoalAndWait(goal, ros::Duration(30.0)); 00305 return (state == al::SimpleClientGoalState::StateEnum::SUCCEEDED); 00306 } 00307 00308 gm::Pose Node::getCurrentPose () 00309 { 00310 while (ros::ok()) 00311 { 00312 if (tf_.waitForTransform("map", "base_footprint", ros::Time(), 00313 ros::Duration(1.0))) 00314 break; 00315 ROS_INFO ("Waiting for robot pose"); 00316 } 00317 tf::StampedTransform base_transform; 00318 tf_.lookupTransform("map", "base_footprint", ros::Time(), base_transform); 00319 gm::Pose pose; 00320 tf::poseTFToMsg(base_transform, pose); 00321 return pose; 00322 00323 } 00324 00325 gm::Polygon Node::getVisibleRegion (const gm::Pose& p) const 00326 { 00327 vector<btVector3> poly(3); 00328 poly[0] = btVector3(0.5, 1.0, 0.0); 00329 poly[1] = btVector3(2.0, 0.0, 0.0); 00330 poly[2] = btVector3(0.5, -1.0, 0.0); 00331 00332 tf::Pose trans; 00333 tf::poseMsgToTF(p, trans); 00334 00335 gm::Polygon polygon; 00336 BOOST_FOREACH (const btVector3& p, poly) 00337 { 00338 btVector3 p2 = (trans*p).asBt(); 00339 gm::Point32 pt; 00340 pt.x = p2.x(); 00341 pt.y = p2.y(); 00342 pt.z = p2.z(); 00343 polygon.points.push_back(pt); 00344 } 00345 return polygon; 00346 } 00347 00348 void Node::updateSeen (const ros::TimerEvent& e) 00349 { 00350 if (!initialized_) 00351 return; 00352 00353 const gm::Pose pose = getCurrentPose(); 00354 gm::PolygonStamped visible_region; 00355 visible_region.polygon = getVisibleRegion(pose); 00356 auto visible_cells = gu::cellsInConvexPolygon(map_->info, 00357 visible_region.polygon); 00358 visible_region.header.frame_id = "/map"; 00359 visible_region.header.stamp = ros::Time::now(); 00360 visible_poly_pub_.publish(visible_region); 00361 Lock l(mutex_); 00362 set<size_t> now_seen; 00363 BOOST_FOREACH (const size_t i, unseen_) 00364 { 00365 if (visible_cells.find(targets_[i])!=visible_cells.end()) 00366 now_seen.insert(i); 00367 } 00368 00369 BOOST_FOREACH (const size_t i, now_seen) 00370 { 00371 unseen_.erase(i); 00372 seen_.insert(i); 00373 } 00374 } 00375 00376 00377 void Node::visualize (const ros::WallTimerEvent& e) 00378 { 00379 Lock l(mutex_); 00380 int id=0; 00381 if (targets_.size()==0) 00382 return; // Not initialized yet 00383 00384 vm::Marker seen; 00385 seen.ns = "search_planes"; 00386 seen.header.frame_id = "/map"; 00387 seen.id = id++; 00388 seen.type = vm::Marker::SPHERE_LIST; 00389 seen.scale.x = seen.scale.y = seen.scale.z = 0.04; 00390 seen.color.b = seen.color.a = 1.0; 00391 00392 vm::Marker unseen = seen; 00393 unseen.id = id++; 00394 unseen.color.r = 1.0; 00395 unseen.color.b = 0.0; 00396 00397 BOOST_FOREACH (const size_t i, seen_) 00398 seen.points.push_back(cellCenter(map_->info, targets_[i])); 00399 vis_pub_.publish(seen); 00400 00401 BOOST_FOREACH (const size_t i, unseen_) 00402 unseen.points.push_back(cellCenter(map_->info, targets_[i])); 00403 vis_pub_.publish(unseen); 00404 00405 00406 for (size_t i=0; i<view_poses_.size(); i++) 00407 { 00408 if (forbidden_.find(i)!=forbidden_.end()) 00409 continue; 00410 00411 vm::Marker m; 00412 m.ns = "search_planes"; 00413 m.header.frame_id = "/map"; 00414 m.id = id++; 00415 m.type = vm::Marker::ARROW; 00416 m.scale.x = 0.7; 00417 m.scale.z = m.scale.z = 0.5; 00418 m.color.g = m.color.a = 1.0; 00419 m.pose = view_poses_[i]; 00420 vis_pub_.publish(m); 00421 } 00422 } 00423 00424 00425 } // namespace 00426 00427 int main (int argc, char** argv) 00428 { 00429 ros::init(argc, argv, "search_for_planes"); 00430 semanticmodel::Node node; 00431 ros::AsyncSpinner spinner(2); 00432 spinner.start(); 00433 node.run(); 00434 return 0; 00435 }