#include <occupancy_grid_display.h>
Protected Member Functions | |
bool | checkType (std::string type_id) |
template<> | |
bool | checkType (std::string type_id) |
template<> | |
bool | checkType (std::string type_id) |
template<> | |
bool | checkType (std::string type_id) |
void | incomingMessageCallback (const octomap_msgs::OctomapConstPtr &msg) |
void | setVoxelColor (rviz::PointCloud::Point &newPoint, typename OcTreeType::NodeType &node, double minZ, double maxZ) |
template<> | |
void | setVoxelColor (PointCloud::Point &newPoint, octomap::ColorOcTree::NodeType &node, double minZ, double maxZ) |
Definition at line 132 of file occupancy_grid_display.h.
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >::checkType | ( | std::string | type_id | ) | [protected] |
Returns false, if the type_id (of the message) does not correspond to the template paramter of this class, true if correct or unknown (i.e., no specialized method for that template).
Definition at line 367 of file occupancy_grid_display.cpp.
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::OcTreeStamped >::checkType | ( | std::string | type_id | ) | [protected] |
Definition at line 375 of file occupancy_grid_display.cpp.
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::OcTree >::checkType | ( | std::string | type_id | ) | [protected] |
Definition at line 381 of file occupancy_grid_display.cpp.
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::ColorOcTree >::checkType | ( | std::string | type_id | ) | [protected] |
Definition at line 388 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >::incomingMessageCallback | ( | const octomap_msgs::OctomapConstPtr & | msg | ) | [protected, virtual] |
Implements octomap_rviz_plugin::OccupancyGridDisplay.
Definition at line 449 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >::setVoxelColor | ( | rviz::PointCloud::Point & | newPoint, |
typename OcTreeType::NodeType & | node, | ||
double | minZ, | ||
double | maxZ | ||
) | [protected] |
Definition at line 395 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::ColorOcTree >::setVoxelColor | ( | PointCloud::Point & | newPoint, |
octomap::ColorOcTree::NodeType & | node, | ||
double | minZ, | ||
double | maxZ | ||
) | [protected] |
Definition at line 420 of file occupancy_grid_display.cpp.