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

Efficiency improvements and customizable occupancy 2D map projection. #9

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
3 changes: 2 additions & 1 deletion octomap_server/cfg/OctomapServer.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,6 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()

gen.add("max_depth", int_t, 0, "Maximum depth when traversing the octree to send out markers. 16: full depth / max. resolution", 16, 1, 16)

gen.add("occupancy_grid_2d_min_z", double_t, 0, "Minimum height for 2D occupancy map projection", 0)
gen.add("occupancy_grid_2d_max_z", double_t, 0, "Maiximum height for 2D occupancy map projection", 3)
exit(gen.generate(PACKAGE, "octomap_server_node", "OctomapServer"))
24 changes: 22 additions & 2 deletions octomap_server/include/octomap_server/OctomapServer.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@
#include <octomap_ros/conversions.h>
#include <octomap/octomap.h>
#include <octomap/OcTreeKey.h>
#include <string>


namespace octomap_server {
Expand All @@ -81,6 +82,7 @@ class OctomapServer{
virtual ~OctomapServer();
virtual bool octomapBinarySrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
virtual bool octomapFullSrv(OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res);
virtual bool octomapPublishAllSrv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
bool clearBBXSrv(BBXSrv::Request& req, BBXSrv::Response& resp);
bool resetSrv(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp);

Expand Down Expand Up @@ -112,7 +114,9 @@ class OctomapServer{
void reconfigureCallback(octomap_server::OctomapServerConfig& config, uint32_t level);
void publishBinaryOctoMap(const ros::Time& rostime = ros::Time::now()) const;
void publishFullOctoMap(const ros::Time& rostime = ros::Time::now()) const;
void publishAll(const ros::Time& rostime = ros::Time::now());
void publishAll(const ros::Time& rostime = ros::Time::now(), bool forceMsgPublish = false);

void insertReferenceOccupancyGrid(const nav_msgs::OccupancyGridConstPtr& occupancy_grid_msg);

/**
* @brief update occupancy map with a scan labeled as ground and nonground.
Expand Down Expand Up @@ -191,7 +195,8 @@ class OctomapServer{
ros::Publisher m_markerPub, m_binaryMapPub, m_fullMapPub, m_pointCloudPub, m_collisionObjectPub, m_mapPub, m_cmapPub, m_fmapPub, m_fmarkerPub;
message_filters::Subscriber<sensor_msgs::PointCloud2>* m_pointCloudSub;
tf::MessageFilter<sensor_msgs::PointCloud2>* m_tfPointCloudSub;
ros::ServiceServer m_octomapBinaryService, m_octomapFullService, m_clearBBXService, m_resetService;
ros::Subscriber m_OccupancyGridSub_;
ros::ServiceServer m_octomapBinaryService, m_octomapFullService, m_octomapPublishAllService, m_clearBBXService, m_resetService;
tf::TransformListener m_tfListener;
dynamic_reconfigure::Server<OctomapServerConfig> m_reconfigureServer;

Expand All @@ -203,6 +208,7 @@ class OctomapServer{
double m_maxRange;
std::string m_worldFrameId; // the map frame
std::string m_baseFrameId; // base of the robot for ground plane filtering
std::string m_sensorFrameId; // the sensor frame
bool m_useHeightMap;
std_msgs::ColorRGBA m_color;
std_msgs::ColorRGBA m_colorFree;
Expand All @@ -218,11 +224,17 @@ class OctomapServer{
double m_probMiss;
double m_thresMin;
double m_thresMax;
double m_thresOccupancy;

bool m_overrideSensorZ;
double m_overrideSensorZValue;
double m_pointcloudMinZ;
double m_pointcloudMaxZ;
double m_occupancyMinZ;
double m_occupancyMaxZ;
double m_occupancyGrid2DMinZ;
double m_occupancyGrid2DMaxZ;
bool m_occupancyGrid2DInitializedAsFree;
double m_minSizeX;
double m_minSizeY;
bool m_filterSpeckles;
Expand All @@ -234,6 +246,14 @@ class OctomapServer{

bool m_compressMap;


ros::Duration m_miniumAmountOfTimeBetweenROSMsgPublishing;
int m_minimumNumberOfIntegrationsBeforeROSMsgPublishing;
ros::Time m_timeLastPublishedROSMsgs;
int m_numberIntegrationsSinceLastPublishedROSMsgs;



// downprojected 2D map:
bool m_incrementalUpdate;
nav_msgs::OccupancyGrid m_gridmap;
Expand Down
Loading