Skip to content

Commit

Permalink
explore: get rid of boost
Browse files Browse the repository at this point in the history
  • Loading branch information
hrnr committed Oct 30, 2017
1 parent 5e65e29 commit fe0e0f3
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 13 deletions.
3 changes: 1 addition & 2 deletions explore/include/explore/costmap_tools.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PolygonStamped.h>
#include <ros/ros.h>
#include <boost/foreach.hpp>

namespace frontier_exploration
{
Expand Down Expand Up @@ -120,7 +119,7 @@ bool nearestCell(unsigned int& result, unsigned int start, unsigned char val,
}

// iterate over all adjacent unvisited cells
BOOST_FOREACH (unsigned nbr, nhood8(idx, costmap)) {
for (unsigned nbr : nhood8(idx, costmap)) {
if (!visited_flag[nbr]) {
bfs.push(nbr);
visited_flag[nbr] = true;
Expand Down
19 changes: 11 additions & 8 deletions explore/src/costmap_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,21 +64,24 @@ Costmap2DClient::Costmap2DClient(ros::NodeHandle& param_nh,
param_nh.param("transform_tolerance", transform_tolerance_, 0.3);

/* initialize costmap */
boost::function<void(const nav_msgs::OccupancyGrid::ConstPtr&)> costmap_cb =
std::bind(&Costmap2DClient::updateFullMap, this, std::placeholders::_1);
costmap_sub_ = subscription_nh.subscribe(costmap_topic, 1000, costmap_cb);
costmap_sub_ = subscription_nh.subscribe<nav_msgs::OccupancyGrid>(
costmap_topic, 1000,
[this](const nav_msgs::OccupancyGrid::ConstPtr& msg) {
updateFullMap(msg);
});
ROS_INFO("Waiting for costmap to become available, topic: %s",
costmap_topic.c_str());
auto costmap_msg = ros::topic::waitForMessage<nav_msgs::OccupancyGrid>(
costmap_topic, subscription_nh);
updateFullMap(costmap_msg);

/* subscribe to map updates */
boost::function<void(const map_msgs::OccupancyGridUpdate::ConstPtr&)>
costmap_updates_cb = std::bind(&Costmap2DClient::updatePartialMap, this,
std::placeholders::_1);
costmap_updates_sub_ = subscription_nh.subscribe(costmap_updates_topic, 1000,
costmap_updates_cb);
costmap_updates_sub_ =
subscription_nh.subscribe<map_msgs::OccupancyGridUpdate>(
costmap_updates_topic, 1000,
[this](const map_msgs::OccupancyGridUpdate::ConstPtr& msg) {
updatePartialMap(msg);
});

/* resolve tf prefix for robot_base_frame */
std::string tf_prefix = tf::getPrefixParam(param_nh);
Expand Down
6 changes: 5 additions & 1 deletion explore/src/explore.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,11 @@ void Explore::makePlan()
goal.target_pose.header.frame_id = costmap_client_.getGlobalFrameID();
goal.target_pose.header.stamp = ros::Time::now();
move_base_client_.sendGoal(
goal, boost::bind(&Explore::reachedGoal, this, _1, _2, target_position));
goal, [this, target_position](
const actionlib::SimpleClientGoalState& status,
const move_base_msgs::MoveBaseResultConstPtr& result) {
reachedGoal(status, result, target_position);
});
}

bool Explore::goalOnBlacklist(const geometry_msgs::Point& goal)
Expand Down
5 changes: 3 additions & 2 deletions explore/src/frontier_search.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include <explore/frontier_search.h>

#include <mutex>

#include <costmap_2d/cost_values.h>
#include <costmap_2d/costmap_2d.h>
#include <geometry_msgs/Point.h>
Expand Down Expand Up @@ -34,8 +36,7 @@ std::vector<Frontier> FrontierSearch::searchFrom(geometry_msgs::Point position)
}

// make sure map is consistent and locked for duration of search
boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(
*(costmap_->getMutex()));
std::lock_guard<costmap_2d::Costmap2D::mutex_t> lock(*(costmap_->getMutex()));

map_ = costmap_->getCharMap();
size_x_ = costmap_->getSizeInCellsX();
Expand Down

0 comments on commit fe0e0f3

Please sign in to comment.