Skip to content

Add style property to change shape of rendered voxels #20

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

Open
wants to merge 1 commit 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 include/octomap_rviz_plugins/occupancy_grid_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ private Q_SLOTS:
void updateAlpha();
void updateMaxHeight();
void updateMinHeight();
void updateStyle();

protected:
// overrides from Display
Expand Down Expand Up @@ -118,6 +119,7 @@ private Q_SLOTS:
rviz::RosTopicProperty* octomap_topic_property_;
rviz::EnumProperty* octree_render_property_;
rviz::EnumProperty* octree_coloring_property_;
rviz::EnumProperty* style_property_;
rviz::IntProperty* tree_depth_property_;
rviz::FloatProperty* alpha_property_;
rviz::FloatProperty* max_height_property_;
Expand Down
19 changes: 18 additions & 1 deletion src/occupancy_grid_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,15 @@ OccupancyGridDisplay::OccupancyGridDisplay() :
"Defines the minimum height to display",
this,
SLOT (updateMinHeight() ));

style_property_ = new EnumProperty( "Style", "Boxes",
"Rendering mode to use, in order of computational complexity.",
this, SLOT( updateStyle() ));
style_property_->addOption( "Points", PointCloud::RM_POINTS );
style_property_->addOption( "Squares", PointCloud::RM_SQUARES );
style_property_->addOption( "Flat Squares", PointCloud::RM_FLAT_SQUARES );
style_property_->addOption( "Spheres", PointCloud::RM_SPHERES );
style_property_->addOption( "Boxes", PointCloud::RM_BOXES );
}

void OccupancyGridDisplay::onInitialize()
Expand All @@ -157,7 +166,7 @@ void OccupancyGridDisplay::onInitialize()
sname << "PointCloud Nr." << i;
cloud_[i] = new rviz::PointCloud();
cloud_[i]->setName(sname.str());
cloud_[i]->setRenderMode(rviz::PointCloud::RM_BOXES);
cloud_[i]->setRenderMode(static_cast<PointCloud::RenderMode>(style_property_->getOptionInt()));
scene_node_->attachObject(cloud_[i]);
}
}
Expand Down Expand Up @@ -315,6 +324,14 @@ void OccupancyGridDisplay::updateMinHeight()
{
}

void OccupancyGridDisplay::updateStyle()
{
for (std::size_t i = 0; i < max_octree_depth_; ++i)
{
cloud_[i]->setRenderMode(static_cast<PointCloud::RenderMode>(style_property_->getOptionInt()));
}
}

void OccupancyGridDisplay::clear()
{

Expand Down