explore.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Robert Bosch LLC.
6  * Copyright (c) 2015-2016, Jiri Horner.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the Jiri Horner nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  *********************************************************************/
37 
38 #include <explore/explore.h>
39 
40 #include <thread>
41 
42 inline static bool operator==(const geometry_msgs::Point& one,
43  const geometry_msgs::Point& two)
44 {
45  double dx = one.x - two.x;
46  double dy = one.y - two.y;
47  double dist = sqrt(dx * dx + dy * dy);
48  return dist < 0.01;
49 }
50 
51 namespace explore
52 {
54  : private_nh_("~")
55  , tf_listener_(ros::Duration(10.0))
56  , costmap_client_(private_nh_, relative_nh_, &tf_listener_)
57  , move_base_client_("move_base")
58  , prev_distance_(0)
59  , last_markers_count_(0)
60 {
61  double timeout;
62  double min_frontier_size;
63  private_nh_.param("planner_frequency", planner_frequency_, 1.0);
64  private_nh_.param("progress_timeout", timeout, 30.0);
66  private_nh_.param("visualize", visualize_, false);
67  private_nh_.param("potential_scale", potential_scale_, 1e-3);
68  private_nh_.param("orientation_scale", orientation_scale_, 0.0);
69  private_nh_.param("gain_scale", gain_scale_, 1.0);
70  private_nh_.param("min_frontier_size", min_frontier_size, 0.5);
71 
74  min_frontier_size);
75 
76  if (visualize_) {
78  private_nh_.advertise<visualization_msgs::MarkerArray>("frontiers", 10);
79  }
80 
81  ROS_INFO("Waiting to connect to move_base server");
83  ROS_INFO("Connected to move_base server");
84 
87  [this](const ros::TimerEvent&) { makePlan(); });
88 }
89 
91 {
92  stop();
93 }
94 
96  const std::vector<frontier_exploration::Frontier>& frontiers)
97 {
98  std_msgs::ColorRGBA blue;
99  blue.r = 0;
100  blue.g = 0;
101  blue.b = 1.0;
102  blue.a = 1.0;
103  std_msgs::ColorRGBA red;
104  red.r = 1.0;
105  red.g = 0;
106  red.b = 0;
107  red.a = 1.0;
108  std_msgs::ColorRGBA green;
109  green.r = 0;
110  green.g = 1.0;
111  green.b = 0;
112  green.a = 1.0;
113 
114  ROS_DEBUG("visualising %lu frontiers", frontiers.size());
115  visualization_msgs::MarkerArray markers_msg;
116  std::vector<visualization_msgs::Marker>& markers = markers_msg.markers;
117  visualization_msgs::Marker m;
118 
119  m.header.frame_id = costmap_client_.getGlobalFrameID();
120  m.header.stamp = ros::Time::now();
121  m.ns = "frontiers";
122  m.scale.x = 1.0;
123  m.scale.y = 1.0;
124  m.scale.z = 1.0;
125  m.color.r = 0;
126  m.color.g = 0;
127  m.color.b = 255;
128  m.color.a = 255;
129  // lives forever
130  m.lifetime = ros::Duration(0);
131  m.frame_locked = true;
132 
133  // weighted frontiers are always sorted
134  double min_cost = frontiers.empty() ? 0. : frontiers.front().cost;
135 
136  m.action = visualization_msgs::Marker::ADD;
137  size_t id = 0;
138  for (auto& frontier : frontiers) {
139  m.type = visualization_msgs::Marker::POINTS;
140  m.id = int(id);
141  m.pose.position = {};
142  m.scale.x = 0.1;
143  m.scale.y = 0.1;
144  m.scale.z = 0.1;
145  m.points = frontier.points;
146  if (goalOnBlacklist(frontier.centroid)) {
147  m.color = red;
148  } else {
149  m.color = blue;
150  }
151  markers.push_back(m);
152  ++id;
153  m.type = visualization_msgs::Marker::SPHERE;
154  m.id = int(id);
155  m.pose.position = frontier.initial;
156  // scale frontier according to its cost (costier frontiers will be smaller)
157  double scale = std::min(std::abs(min_cost * 0.4 / frontier.cost), 0.5);
158  m.scale.x = scale;
159  m.scale.y = scale;
160  m.scale.z = scale;
161  m.points = {};
162  m.color = green;
163  markers.push_back(m);
164  ++id;
165  }
166  size_t current_markers_count = markers.size();
167 
168  // delete previous markers, which are now unused
169  m.action = visualization_msgs::Marker::DELETE;
170  for (; id < last_markers_count_; ++id) {
171  m.id = int(id);
172  markers.push_back(m);
173  }
174 
175  last_markers_count_ = current_markers_count;
176  marker_array_publisher_.publish(markers_msg);
177 }
178 
180 {
181  // find frontiers
182  auto pose = costmap_client_.getRobotPose();
183  // get frontiers sorted according to cost
184  auto frontiers = search_.searchFrom(pose.position);
185  ROS_DEBUG("found %lu frontiers", frontiers.size());
186  for (size_t i = 0; i < frontiers.size(); ++i) {
187  ROS_DEBUG("frontier %zd cost: %f", i, frontiers[i].cost);
188  }
189 
190  if (frontiers.empty()) {
191  stop();
192  return;
193  }
194 
195  // publish frontiers as visualization markers
196  if (visualize_) {
197  visualizeFrontiers(frontiers);
198  }
199 
200  // find non blacklisted frontier
201  auto frontier =
202  std::find_if_not(frontiers.begin(), frontiers.end(),
203  [this](const frontier_exploration::Frontier& f) {
204  return goalOnBlacklist(f.centroid);
205  });
206  if (frontier == frontiers.end()) {
207  stop();
208  return;
209  }
210  geometry_msgs::Point target_position = frontier->centroid;
211 
212  // time out if we are not making any progress
213  bool same_goal = prev_goal_ == target_position;
214  prev_goal_ = target_position;
215  if (!same_goal || prev_distance_ > frontier->min_distance) {
216  // we have different goal or we made some progress
218  prev_distance_ = frontier->min_distance;
219  }
220  // black list if we've made no progress for a long time
222  frontier_blacklist_.push_back(target_position);
223  ROS_DEBUG("Adding current goal to black list");
224  makePlan();
225  return;
226  }
227 
228  // we don't need to do anything if we still pursuing the same goal
229  if (same_goal) {
230  return;
231  }
232 
233  // send goal to move_base if we have something new to pursue
234  move_base_msgs::MoveBaseGoal goal;
235  goal.target_pose.pose.position = target_position;
236  goal.target_pose.pose.orientation.w = 1.;
237  goal.target_pose.header.frame_id = costmap_client_.getGlobalFrameID();
238  goal.target_pose.header.stamp = ros::Time::now();
240  goal, [this, target_position](
241  const actionlib::SimpleClientGoalState& status,
242  const move_base_msgs::MoveBaseResultConstPtr& result) {
243  reachedGoal(status, result, target_position);
244  });
245 }
246 
247 bool Explore::goalOnBlacklist(const geometry_msgs::Point& goal)
248 {
249  constexpr static size_t tolerace = 5;
251 
252  // check if a goal is on the blacklist for goals that we're pursuing
253  for (auto& frontier_goal : frontier_blacklist_) {
254  double x_diff = fabs(goal.x - frontier_goal.x);
255  double y_diff = fabs(goal.y - frontier_goal.y);
256 
257  if (x_diff < tolerace * costmap2d->getResolution() &&
258  y_diff < tolerace * costmap2d->getResolution())
259  return true;
260  }
261  return false;
262 }
263 
265  const move_base_msgs::MoveBaseResultConstPtr&,
266  const geometry_msgs::Point& frontier_goal)
267 {
268  ROS_DEBUG("Reached goal with status: %s", status.toString().c_str());
270  frontier_blacklist_.push_back(frontier_goal);
271  ROS_DEBUG("Adding current goal to black list");
272  }
273 
274  // find new goal immediatelly regardless of planning frequency.
275  // execute via timer to prevent dead lock in move_base_client (this is
276  // callback for sendGoal, which is called in makePlan). the timer must live
277  // until callback is executed.
279  ros::Duration(0, 0), [this](const ros::TimerEvent&) { makePlan(); },
280  true);
281 }
282 
284 {
286 }
287 
289 {
292  ROS_INFO("Exploration stopped.");
293 }
294 
295 } // namespace explore
296 
297 int main(int argc, char** argv)
298 {
299  ros::init(argc, argv, "explore");
303  }
305  ros::spin();
306 
307  return 0;
308 }
ros::Duration progress_timeout_
Definition: explore.h:109
double potential_scale_
Definition: explore.h:108
void visualizeFrontiers(const std::vector< frontier_exploration::Frontier > &frontiers)
Publish a frontiers as markers.
Definition: explore.cpp:95
double gain_scale_
Definition: explore.h:108
ros::Timer oneshot_
Definition: explore.h:98
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void publish(const boost::shared_ptr< M > &message) const
f
ros::Time last_progress_
Definition: explore.h:103
size_t last_markers_count_
Definition: explore.h:104
double planner_frequency_
Definition: explore.h:107
std::vector< geometry_msgs::Point > frontier_blacklist_
Definition: explore.h:100
double orientation_scale_
Definition: explore.h:108
void stop()
geometry_msgs::Pose getRobotPose() const
Get the pose of the robot in the global frame of the costmap.
costmap_2d::Costmap2D * getCostmap()
Return a pointer to the "master" costmap which receives updates from all the layers.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void start()
void reachedGoal(const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, const geometry_msgs::Point &frontier_goal)
Definition: explore.cpp:264
ros::Timer exploring_timer_
Definition: explore.h:97
bool goalOnBlacklist(const geometry_msgs::Point &goal)
Definition: explore.cpp:247
int main(int argc, char **argv)
Definition: explore.cpp:297
ros::NodeHandle private_nh_
Definition: explore.h:88
geometry_msgs::Point prev_goal_
Definition: explore.h:101
static bool operator==(const geometry_msgs::Point &one, const geometry_msgs::Point &two)
Definition: explore.cpp:42
Represents a frontier.
ROSCPP_DECL void spin(Spinner &spinner)
std::string toString() const
double prev_distance_
Definition: explore.h:102
const std::string & getGlobalFrameID() const
Returns the global frame of the costmap.
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
A class adhering to the robot_actions::Action interface that moves the robot base to explore its envi...
Definition: explore.h:61
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
frontier_exploration::FrontierSearch search_
Definition: explore.h:96
void makePlan()
Make a global plan.
Definition: explore.cpp:179
Thread-safe implementation of a frontier-search task for an input costmap.
ros::NodeHandle relative_nh_
Definition: explore.h:89
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ros::Publisher marker_array_publisher_
Definition: explore.h:90
static Time now()
std::vector< Frontier > searchFrom(geometry_msgs::Point position)
Runs search implementation, outward from the start position.
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > move_base_client_
Definition: explore.h:95
#define ROSCONSOLE_DEFAULT_NAME
Costmap2DClient costmap_client_
Definition: explore.h:93
#define ROS_DEBUG(...)


explore
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:49