42 inline static bool operator==(
const geometry_msgs::Point& one,
43 const geometry_msgs::Point& two)
45 double dx = one.x - two.x;
46 double dy = one.y - two.y;
47 double dist = sqrt(dx * dx + dy * dy);
55 , tf_listener_(
ros::Duration(10.0))
56 , costmap_client_(private_nh_, relative_nh_, &tf_listener_)
57 , move_base_client_(
"move_base")
59 , last_markers_count_(0)
62 double min_frontier_size;
81 ROS_INFO(
"Waiting to connect to move_base server");
83 ROS_INFO(
"Connected to move_base server");
96 const std::vector<frontier_exploration::Frontier>& frontiers)
98 std_msgs::ColorRGBA blue;
103 std_msgs::ColorRGBA red;
108 std_msgs::ColorRGBA green;
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;
131 m.frame_locked =
true;
134 double min_cost = frontiers.empty() ? 0. : frontiers.front().cost;
136 m.action = visualization_msgs::Marker::ADD;
138 for (
auto& frontier : frontiers) {
139 m.type = visualization_msgs::Marker::POINTS;
141 m.pose.position = {};
145 m.points = frontier.points;
151 markers.push_back(m);
153 m.type = visualization_msgs::Marker::SPHERE;
155 m.pose.position = frontier.initial;
157 double scale = std::min(std::abs(min_cost * 0.4 / frontier.cost), 0.5);
163 markers.push_back(m);
166 size_t current_markers_count = markers.size();
169 m.action = visualization_msgs::Marker::DELETE;
172 markers.push_back(m);
175 last_markers_count_ = current_markers_count;
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);
190 if (frontiers.empty()) {
202 std::find_if_not(frontiers.begin(), frontiers.end(),
206 if (frontier == frontiers.end()) {
210 geometry_msgs::Point target_position = frontier->centroid;
213 bool same_goal =
prev_goal_ == target_position;
223 ROS_DEBUG(
"Adding current goal to black list");
234 move_base_msgs::MoveBaseGoal goal;
235 goal.target_pose.pose.position = target_position;
236 goal.target_pose.pose.orientation.w = 1.;
240 goal, [
this, target_position](
242 const move_base_msgs::MoveBaseResultConstPtr& result) {
249 constexpr
static size_t tolerace = 5;
254 double x_diff = fabs(goal.x - frontier_goal.x);
255 double y_diff = fabs(goal.y - frontier_goal.y);
257 if (x_diff < tolerace * costmap2d->getResolution() &&
258 y_diff < tolerace * costmap2d->getResolution())
265 const move_base_msgs::MoveBaseResultConstPtr&,
266 const geometry_msgs::Point& frontier_goal)
271 ROS_DEBUG(
"Adding current goal to black list");
297 int main(
int argc,
char** argv)
ros::Duration progress_timeout_
void visualizeFrontiers(const std::vector< frontier_exploration::Frontier > &frontiers)
Publish a frontiers as markers.
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void publish(const boost::shared_ptr< M > &message) const
size_t last_markers_count_
double planner_frequency_
std::vector< geometry_msgs::Point > frontier_blacklist_
double orientation_scale_
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 reachedGoal(const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, const geometry_msgs::Point &frontier_goal)
ros::Timer exploring_timer_
bool goalOnBlacklist(const geometry_msgs::Point &goal)
int main(int argc, char **argv)
ros::NodeHandle private_nh_
geometry_msgs::Point prev_goal_
static bool operator==(const geometry_msgs::Point &one, const geometry_msgs::Point &two)
ROSCPP_DECL void spin(Spinner &spinner)
std::string toString() const
const std::string & getGlobalFrameID() const
Returns the global frame of the costmap.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
A class adhering to the robot_actions::Action interface that moves the robot base to explore its envi...
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_
void makePlan()
Make a global plan.
Thread-safe implementation of a frontier-search task for an input costmap.
ros::NodeHandle relative_nh_
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
ros::Publisher marker_array_publisher_
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_
#define ROSCONSOLE_DEFAULT_NAME
Costmap2DClient costmap_client_