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

Implemented a more recent function from octomap for incredible speed up #47

Open
wants to merge 2 commits into
base: kinetic-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
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
octomap_mapping
===============

Forked by Yonder Dynamics to implement latest features of octomap lib that allow for a 10x speed up.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changes to README would have to be reverted prior to this pull request being merged.


ROS stack for mapping with OctoMap, contains the octomap_server package.

Expand Down
14 changes: 11 additions & 3 deletions octomap_server/src/OctomapServer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -361,7 +361,15 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
{
ROS_ERROR_STREAM("Could not generate Key for origin "<<sensorOrigin);
}
// Generate octomap pointcloud
Pointcloud pc;
for (PCLPointCloud::const_iterator it = nonground.begin(); it != nonground.end(); ++it){
pc.push_back(it->x, it->y, it->z);
}
m_octree->insertPointCloud (pc, sensorOrigin, m_maxRange, true, true);
m_octree->updateInnerOccupancy();

/*
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Small change in this line, but you essentially replaced all of the specialized point cloud handling in the next 100 lines with the default OctoMap point cloud insertion, and hardcoded the option "discretize"=true. This could be done as speedup, but better as an optional parameter to octomap_server, because it creates different maps in the end (less information in them).

You also only insert the "nonground" point cloud, while the commented out 100 lines insert both ground and nonground, and give the option to filter out ground points while still using them for clearing obstacles - this is a significantly different behavior and different maps will be created in the end.

#ifdef COLOR_OCTOMAP_SERVER
unsigned char* colors = new unsigned char[3];
#endif
Expand Down Expand Up @@ -471,16 +479,16 @@ void OctomapServer::insertScan(const tf::Point& sensorOriginTf, const PCLPointCl
ROS_DEBUG_STREAM("Updated area bounding box: "<< minPt << " - "<<maxPt);
ROS_DEBUG_STREAM("Bounding box keys (after): " << m_updateBBXMin[0] << " " <<m_updateBBXMin[1] << " " << m_updateBBXMin[2] << " / " <<m_updateBBXMax[0] << " "<<m_updateBBXMax[1] << " "<< m_updateBBXMax[2]);

if (m_compressMap)
m_octree->prune();

#ifdef COLOR_OCTOMAP_SERVER
if (colors)
{
delete[] colors;
colors = NULL;
}
#endif
*/
if (m_compressMap)
m_octree->prune();
}


Expand Down
1 change: 1 addition & 0 deletions octomap_server/src/octomap_server_static.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,7 @@ int main(int argc, char** argv){
}

try{
ROS_INFO("Started");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this required?

OctomapServerStatic ms(mapFilename);
ros::spin();
}catch(std::runtime_error& e){
Expand Down