explore.h
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 #ifndef NAV_EXPLORE_H_
38 #define NAV_EXPLORE_H_
39 
40 #include <memory>
41 #include <mutex>
42 #include <string>
43 #include <vector>
44 
46 #include <geometry_msgs/PoseStamped.h>
47 #include <move_base_msgs/MoveBaseAction.h>
48 #include <ros/ros.h>
49 #include <visualization_msgs/MarkerArray.h>
50 
51 #include <explore/costmap_client.h>
53 
54 namespace explore
55 {
61 class Explore
62 {
63 public:
64  Explore();
65  ~Explore();
66 
67  void start();
68  void stop();
69 
70 private:
74  void makePlan();
75 
79  void visualizeFrontiers(
80  const std::vector<frontier_exploration::Frontier>& frontiers);
81 
83  const move_base_msgs::MoveBaseResultConstPtr& result,
84  const geometry_msgs::Point& frontier_goal);
85 
86  bool goalOnBlacklist(const geometry_msgs::Point& goal);
87 
92 
99 
100  std::vector<geometry_msgs::Point> frontier_blacklist_;
101  geometry_msgs::Point prev_goal_;
105 
106  // parameters
111 };
112 }
113 
114 #endif
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
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 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
ros::NodeHandle private_nh_
Definition: explore.h:88
geometry_msgs::Point prev_goal_
Definition: explore.h:101
tf::TransformListener tf_listener_
Definition: explore.h:91
double prev_distance_
Definition: explore.h:102
A class adhering to the robot_actions::Action interface that moves the robot base to explore its envi...
Definition: explore.h:61
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
ros::Publisher marker_array_publisher_
Definition: explore.h:90
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > move_base_client_
Definition: explore.h:95
Costmap2DClient costmap_client_
Definition: explore.h:93


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