Protected Member Functions | List of all members
octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType > Class Template Reference

#include <occupancy_grid_display.h>

Inheritance diagram for octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >:
Inheritance graph
[legend]

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)
 
- Protected Member Functions inherited from octomap_rviz_plugin::OccupancyGridDisplay
void clear ()
 
virtual void onDisable ()
 
virtual void onEnable ()
 
void setColor (double z_pos, double min_z, double max_z, double color_factor, rviz::PointCloud::Point &point)
 
void subscribe ()
 
void unsubscribe ()
 
virtual bool updateFromTF ()
 
- Protected Member Functions inherited from rviz::Display
virtual void clearStatuses ()
 
virtual void fixedFrameChanged ()
 
bool initialized () const
 
- Protected Member Functions inherited from rviz::Property
void loadValue (const Config &config)
 

Additional Inherited Members

- Public Slots inherited from rviz::Display
virtual void onEnableChanged ()
 
void queueRender ()
 
void setEnabled (bool enabled)
 
virtual void setIcon (const QIcon &icon)
 
- Public Slots inherited from rviz::BoolProperty
bool setBool (bool value)
 
- Signals inherited from rviz::Display
void timeSignal (rviz::Display *display, ros::Time time)
 
- Signals inherited from rviz::Property
void aboutToChange ()
 
void changed ()
 
void childListChanged (Property *this_property)
 
- Public Member Functions inherited from octomap_rviz_plugin::OccupancyGridDisplay
 OccupancyGridDisplay ()
 
virtual void onInitialize ()
 
virtual void reset ()
 
virtual void update (float wall_dt, float ros_dt)
 
virtual ~OccupancyGridDisplay ()
 
- Public Member Functions inherited from rviz::Display
virtual void deleteStatus (const QString &name)
 
void deleteStatusStd (const std::string &name)
 
 Display ()
 
void emitTimeSignal (ros::Time time)
 
QWidget * getAssociatedWidget () const
 
PanelDockWidgetgetAssociatedWidgetPanel ()
 
virtual QString getClassId () const
 
Ogre::SceneNode * getSceneNode () const
 
virtual QVariant getViewData (int column, int role) const
 
virtual Qt::ItemFlags getViewFlags (int column) const
 
uint32_t getVisibilityBits ()
 
void initialize (DisplayContext *context)
 
bool isEnabled () const
 
virtual void load (const Config &config)
 
virtual void save (Config config) const
 
void setAssociatedWidget (QWidget *widget)
 
virtual void setClassId (const QString &class_id)
 
void setFixedFrame (const QString &fixed_frame)
 
void setName (const QString &name)
 
virtual void setStatus (StatusProperty::Level level, const QString &name, const QString &text)
 
void setStatusStd (StatusProperty::Level level, const std::string &name, const std::string &text)
 
virtual void setTopic (const QString &topic, const QString &datatype)
 
void setVisibilityBits (uint32_t bits)
 
void unsetVisibilityBits (uint32_t bits)
 
virtual ~Display ()
 
- Public Member Functions inherited from rviz::BoolProperty
 BoolProperty (const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)
 
virtual bool getBool () const
 
virtual bool getDisableChildren ()
 
bool getDisableChildrenIfFalse ()
 
void setDisableChildrenIfFalse (bool disable)
 
virtual ~BoolProperty ()
 
- Public Member Functions inherited from rviz::Property
virtual void addChild (Property *child, int index=-1)
 
PropertychildAt (int index) const
 
virtual PropertychildAtUnchecked (int index) const
 
virtual void collapse ()
 
bool contains (Property *possible_child) const
 
virtual QWidget * createEditor (QWidget *parent, const QStyleOptionViewItem &option)
 
virtual void expand ()
 
virtual QString getDescription () const
 
virtual bool getHidden () const
 
virtual QIcon getIcon () const
 
PropertyTreeModelgetModel () const
 
virtual QString getName () const
 
std::string getNameStd () const
 
PropertygetParent () const
 
virtual bool getReadOnly ()
 
virtual QVariant getValue () const
 
void hide ()
 
bool isAncestorOf (Property *possible_child) const
 
virtual void moveChild (int from_index, int to_index)
 
virtual int numChildren () const
 
virtual bool paint (QPainter *painter, const QStyleOptionViewItem &option) const
 
 Property (const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)
 
virtual void removeChildren (int start_index=0, int count=-1)
 
int rowNumberInParent () const
 
virtual void setDescription (const QString &description)
 
virtual void setHidden (bool hidden)
 
virtual void setIcon (const QIcon &icon)
 
void setModel (PropertyTreeModel *model)
 
void setParent (Property *new_parent)
 
virtual void setReadOnly (bool read_only)
 
void setShouldBeSaved (bool save)
 
virtual bool setValue (const QVariant &new_value)
 
bool shouldBeSaved () const
 
void show ()
 
virtual PropertysubProp (const QString &sub_name)
 
PropertytakeChild (Property *child)
 
virtual PropertytakeChildAt (int index)
 
virtual ~Property ()
 
- Protected Types inherited from octomap_rviz_plugin::OccupancyGridDisplay
typedef std::vector< rviz::PointCloud::PointVPoint
 
typedef std::vector< VPointVVPoint
 
- Protected Attributes inherited from octomap_rviz_plugin::OccupancyGridDisplay
rviz::FloatPropertyalpha_property_
 
std::vector< double > box_size_
 
std::vector< rviz::PointCloud * > cloud_
 
double color_factor_
 
std_msgs::Header header_
 
rviz::FloatPropertymax_height_property_
 
uint32_t messages_received_
 
rviz::FloatPropertymin_height_property_
 
boost::mutex mutex_
 
VVPoint new_points_
 
bool new_points_received_
 
rviz::RosTopicPropertyoctomap_topic_property_
 
rviz::EnumPropertyoctree_coloring_property_
 
rviz::EnumPropertyoctree_render_property_
 
VVPoint point_buf_
 
u_int32_t queue_size_
 
rviz::IntPropertyqueue_size_property_
 
boost::shared_ptr< message_filters::Subscriber< octomap_msgs::Octomap > > sub_
 
rviz::IntPropertytree_depth_property_
 
- Protected Attributes inherited from rviz::Display
DisplayContextcontext_
 
QString fixed_frame_
 
Ogre::SceneManager * scene_manager_
 
Ogre::SceneNode * scene_node_
 
ros::NodeHandle threaded_nh_
 
ros::NodeHandle update_nh_
 
- Protected Attributes inherited from rviz::Property
bool child_indexes_valid_
 
QIcon icon_
 
PropertyTreeModelmodel_
 
QVariant value_
 

Detailed Description

template<typename OcTreeType>
class octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >

Definition at line 135 of file occupancy_grid_display.h.

Member Function Documentation

template<typename OcTreeType >
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 374 of file occupancy_grid_display.cpp.

template<>
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::OcTreeStamped >::checkType ( std::string  type_id)
protected

Definition at line 382 of file occupancy_grid_display.cpp.

template<>
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::OcTree >::checkType ( std::string  type_id)
protected

Definition at line 388 of file occupancy_grid_display.cpp.

template<>
bool octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::ColorOcTree >::checkType ( std::string  type_id)
protected

Definition at line 395 of file occupancy_grid_display.cpp.

template<typename OcTreeType >
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >::incomingMessageCallback ( const octomap_msgs::OctomapConstPtr &  msg)
protectedvirtual
template<typename OcTreeType >
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< OcTreeType >::setVoxelColor ( rviz::PointCloud::Point newPoint,
typename OcTreeType::NodeType &  node,
double  minZ,
double  maxZ 
)
protected

Definition at line 402 of file occupancy_grid_display.cpp.

template<>
void octomap_rviz_plugin::TemplatedOccupancyGridDisplay< octomap::ColorOcTree >::setVoxelColor ( PointCloud::Point newPoint,
octomap::ColorOcTree::NodeType node,
double  minZ,
double  maxZ 
)
protected

Definition at line 427 of file occupancy_grid_display.cpp.


The documentation for this class was generated from the following files:


octomap_rviz_plugins
Author(s): Julius Kammerl
autogenerated on Wed Jan 20 2021 03:10:01