-
Notifications
You must be signed in to change notification settings - Fork 281
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
base: kinetic-devel
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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(); | ||
|
||
/* | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 | ||
|
@@ -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(); | ||
} | ||
|
||
|
||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -143,6 +143,7 @@ int main(int argc, char** argv){ | |
} | ||
|
||
try{ | ||
ROS_INFO("Started"); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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){ | ||
|
There was a problem hiding this comment.
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.