#include <occupancy_grid_display.h>
Definition at line 57 of file occupancy_grid_display.h.
typedef std::vector<rviz::PointCloud::Point> octomap_rviz_plugin::OccupancyGridDisplay::VPoint [protected] |
Definition at line 91 of file occupancy_grid_display.h.
typedef std::vector<VPoint> octomap_rviz_plugin::OccupancyGridDisplay::VVPoint [protected] |
Definition at line 92 of file occupancy_grid_display.h.
Definition at line 73 of file occupancy_grid_display.cpp.
Definition at line 143 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::clear | ( | ) | [protected] |
Definition at line 431 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::incomingMessageCallback | ( | const octomap_msgs::OctomapConstPtr & | msg | ) | [protected] |
Definition at line 272 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::onDisable | ( | ) | [protected, virtual] |
Reimplemented from rviz::Display.
Definition at line 170 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::onEnable | ( | ) | [protected, virtual] |
Reimplemented from rviz::Display.
Definition at line 164 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::onInitialize | ( | ) | [virtual] |
Reimplemented from rviz::Display.
Definition at line 123 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::reset | ( | ) | [virtual] |
Reimplemented from rviz::Display.
Definition at line 464 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::setColor | ( | double | z_pos, |
double | min_z, | ||
double | max_z, | ||
double | color_factor, | ||
rviz::PointCloud::Point & | point | ||
) | [protected] |
Definition at line 225 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::subscribe | ( | ) | [protected] |
Definition at line 178 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::unsubscribe | ( | ) | [protected] |
Definition at line 208 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::update | ( | float | wall_dt, |
float | ros_dt | ||
) | [virtual] |
Reimplemented from rviz::Display.
Definition at line 443 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::updateOctreeColorMode | ( | ) | [private, slot] |
Definition at line 427 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::updateOctreeRenderMode | ( | ) | [private, slot] |
Definition at line 423 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::updateQueueSize | ( | ) | [private, slot] |
Definition at line 157 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::updateTopic | ( | ) | [private, slot] |
Definition at line 471 of file occupancy_grid_display.cpp.
void octomap_rviz_plugin::OccupancyGridDisplay::updateTreeDepth | ( | ) | [private, slot] |
Definition at line 419 of file occupancy_grid_display.cpp.
std::vector<double> octomap_rviz_plugin::OccupancyGridDisplay::box_size_ [protected] |
Definition at line 105 of file occupancy_grid_display.h.
std::vector<rviz::PointCloud*> octomap_rviz_plugin::OccupancyGridDisplay::cloud_ [protected] |
Definition at line 104 of file occupancy_grid_display.h.
double octomap_rviz_plugin::OccupancyGridDisplay::color_factor_ [protected] |
Definition at line 117 of file occupancy_grid_display.h.
uint32_t octomap_rviz_plugin::OccupancyGridDisplay::messages_received_ [protected] |
Definition at line 116 of file occupancy_grid_display.h.
boost::mutex octomap_rviz_plugin::OccupancyGridDisplay::mutex_ [protected] |
Definition at line 96 of file occupancy_grid_display.h.
Definition at line 99 of file occupancy_grid_display.h.
bool octomap_rviz_plugin::OccupancyGridDisplay::new_points_received_ [protected] |
Definition at line 101 of file occupancy_grid_display.h.
rviz::RosTopicProperty* octomap_rviz_plugin::OccupancyGridDisplay::octomap_topic_property_ [protected] |
Definition at line 109 of file occupancy_grid_display.h.
rviz::EnumProperty* octomap_rviz_plugin::OccupancyGridDisplay::octree_coloring_property_ [protected] |
Definition at line 111 of file occupancy_grid_display.h.
std::size_t octomap_rviz_plugin::OccupancyGridDisplay::octree_depth_ [protected] |
Definition at line 115 of file occupancy_grid_display.h.
Definition at line 110 of file occupancy_grid_display.h.
Definition at line 100 of file occupancy_grid_display.h.
u_int32_t octomap_rviz_plugin::OccupancyGridDisplay::queue_size_ [protected] |
Definition at line 114 of file occupancy_grid_display.h.
Definition at line 108 of file occupancy_grid_display.h.
boost::shared_ptr<message_filters::Subscriber<octomap_msgs::Octomap> > octomap_rviz_plugin::OccupancyGridDisplay::sub_ [protected] |
Definition at line 94 of file occupancy_grid_display.h.
Definition at line 112 of file occupancy_grid_display.h.