Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[octomap_server] Update inner occupancy periodically #36

Open
wants to merge 1 commit into
base: indigo-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions octomap_server/include/octomap_server/OctomapServer.h
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,7 @@ class OctomapServer {
void publishBinaryOctoMap(const ros::Time& rostime = ros::Time::now()) const;
void publishFullOctoMap(const ros::Time& rostime = ros::Time::now()) const;
virtual void publishAll(const ros::Time& rostime = ros::Time::now());
void updateInnerOccupancy(const ros::TimerEvent& event);

/**
* @brief update occupancy map with a scan labeled as ground and nonground.
Expand Down
11 changes: 11 additions & 0 deletions octomap_server/src/OctomapServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,12 @@ OctomapServer::OctomapServer(ros::NodeHandle private_nh_)
dynamic_reconfigure::Server<OctomapServerConfig>::CallbackType f;
f = boost::bind(&OctomapServer::reconfigureCallback, this, _1, _2);
m_reconfigureServer.setCallback(f);

private_nh.createTimer(
ros::Duration(1),
&OctomapServer::updateInnerOccupancy,
this,
/*oneshot=*/false);
}

OctomapServer::~OctomapServer(){
Expand Down Expand Up @@ -477,6 +483,11 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
}


void OctomapServer::updateInnerOccupancy(const ros::TimerEvent& event)
{
m_octree->updateInnerOccupancy();
}


void OctomapServer::publishAll(const ros::Time& rostime){
ros::WallTime startTime = ros::WallTime::now();
Expand Down
3 changes: 2 additions & 1 deletion octomap_server/src/octomap_server_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,8 @@ int main(int argc, char** argv){
}

try{
ros::spin();
ros::MultiThreadedSpinner spinner(4);
spinner.spin();
}catch(std::runtime_error& e){
ROS_ERROR("octomap_server exception: %s", e.what());
return -1;
Expand Down