Displays a point cloud of type sensor_msgs::PointCloud2. More...
#include <point_cloud2_display.h>
Public Member Functions | |
PointCloud2Display () | |
void | reset () override |
Called to tell the display to clear its state. More... | |
void | update (float wall_dt, float ros_dt) override |
Called periodically by the visualization manager. More... | |
~PointCloud2Display () override | |
Public Member Functions inherited from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 > | |
MessageFilterDisplay () | |
void | onInitialize () override |
Override this function to do subclass-specific initialization. More... | |
void | reset () override |
Called to tell the display to clear its state. More... | |
void | setTopic (const QString &topic, const QString &) override |
Set the ROS topic to listen to for this display. More... | |
~MessageFilterDisplay () override | |
Public Member Functions inherited from rviz::_RosTopicDisplay | |
_RosTopicDisplay () | |
Public Member Functions inherited from rviz::Display | |
virtual void | deleteStatus (const QString &name) |
Delete the status entry with the given name. This is thread-safe. More... | |
void | deleteStatusStd (const std::string &name) |
Delete the status entry with the given std::string name. This is thread-safe. More... | |
Display () | |
void | emitTimeSignal (ros::Time time) |
Emit a time signal that other Displays can synchronize to. More... | |
QWidget * | getAssociatedWidget () const |
Return the current associated widget, or NULL if there is none. More... | |
PanelDockWidget * | getAssociatedWidgetPanel () |
Return the panel containing the associated widget, or NULL if there is none. More... | |
virtual QString | getClassId () const |
Return the class identifier which was used to create this instance. This version just returns whatever was set with setClassId(). More... | |
Ogre::SceneNode * | getSceneNode () const |
Return the Ogre::SceneNode holding all 3D scene elements shown by this Display. More... | |
QVariant | getViewData (int column, int role) const override |
Return data appropriate for the given column (0 or 1) and role for this Display. More... | |
Qt::ItemFlags | getViewFlags (int column) const override |
Return item flags appropriate for the given column (0 or 1) for this Display. More... | |
uint32_t | getVisibilityBits () |
void | initialize (DisplayContext *context) |
Main initialization, called after constructor, before load() or setEnabled(). More... | |
bool | isEnabled () const |
Return true if this Display is enabled, false if not. More... | |
void | load (const Config &config) override |
Load the settings for this display from the given Config node, which must be a map. More... | |
void | save (Config config) const override |
Write this display to the given Config node. More... | |
void | setAssociatedWidget (QWidget *widget) |
Associate the given widget with this Display. More... | |
virtual void | setClassId (const QString &class_id) |
Set the class identifier used to create this instance. Typically this will be set by the factory object which created it. More... | |
void | setFixedFrame (const QString &fixed_frame) |
Set the fixed frame in this display. More... | |
void | setName (const QString &name) override |
Overridden from Property to set associated widget title to the new name. More... | |
virtual void | setStatus (StatusProperty::Level level, const QString &name, const QString &text) |
Show status level and text. This is thread-safe. More... | |
void | setStatusStd (StatusProperty::Level level, const std::string &name, const std::string &text) |
Show status level and text, using a std::string. Convenience function which converts std::string to QString and calls setStatus(). This is thread-safe. More... | |
void | setVisibilityBits (uint32_t bits) |
void | unsetVisibilityBits (uint32_t bits) |
~Display () override | |
Public Member Functions inherited from rviz::BoolProperty | |
template<typename Func , typename P > | |
BoolProperty (const QString &name, bool default_value, const QString &description, P *parent, Func &&changed_slot) | |
template<typename Func , typename R > | |
BoolProperty (const QString &name, bool default_value, const QString &description, Property *parent, Func &&changed_slot, const R *receiver) | |
BoolProperty (const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr) | |
virtual bool | getBool () const |
bool | getDisableChildren () override |
If true, the children of this property should set their ItemIsEnabled flag to false. More... | |
bool | getDisableChildrenIfFalse () |
void | setDisableChildrenIfFalse (bool disable) |
~BoolProperty () override | |
Public Member Functions inherited from rviz::Property | |
virtual void | addChild (Property *child, int index=-1) |
Add a child property. More... | |
Property * | childAt (int index) const |
Return the child Property with the given index, or NULL if the index is out of bounds or if the child at that index is not a Property. More... | |
virtual Property * | childAtUnchecked (int index) const |
Return the child Property with the given index, without checking whether the index is within bounds. More... | |
virtual void | collapse () |
Collapse (hide the children of) this Property. More... | |
template<typename Func > | |
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type | connect (const QObject *context, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection) |
Connect changed() signal to given slot functor, considering context. More... | |
QMetaObject::Connection | connect (const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection) |
Connect changed() signal to given slot of receiver. More... | |
template<typename Func , typename R > | |
std::enable_if< QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type | connect (const R *receiver, Func &&slot, Qt::ConnectionType type=Qt::AutoConnection) |
Connect changed() signal to given slot member function of receiver object. More... | |
template<typename Func > | |
std::enable_if<!QtPrivate::FunctionPointer< Func >::IsPointerToMemberFunction, QMetaObject::Connection >::type | connect (Func &&slot, Qt::ConnectionType type=Qt::AutoConnection) |
Connect changed() signal to given slot functor, using this as context. More... | |
bool | contains (Property *possible_child) const |
Return true if the list of children includes possible_child, false if not. More... | |
virtual QWidget * | createEditor (QWidget *parent, const QStyleOptionViewItem &option) |
Create an editor widget to edit the value of this property. More... | |
virtual void | expand () |
Expand (show the children of) this Property. More... | |
virtual QString | getDescription () const |
Return the description. More... | |
virtual bool | getHidden () const |
Return the hidden/shown state. True means hidden, false means visible. More... | |
virtual QIcon | getIcon () const |
PropertyTreeModel * | getModel () const |
Return the model managing this Property and its childrent. More... | |
virtual QString | getName () const |
Return the name of this Property as a QString. More... | |
std::string | getNameStd () const |
Return the name of this Property as a std::string. More... | |
Property * | getParent () const |
Return the parent Property. More... | |
virtual bool | getReadOnly () const |
Return the read-only-ness of this property. More... | |
virtual QVariant | getValue () const |
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant is returned. More... | |
void | hide () |
Hide this Property in any PropertyTreeWidgets. More... | |
void | insertChildSorted (Property *child) |
Insert a child property, sorted by name. More... | |
bool | isAncestorOf (Property *possible_child) const |
Returns true if this is an ancestor of possible_child, meaning is the parent or parent of parent etc. More... | |
virtual void | moveChild (int from_index, int to_index) |
Move the child at from_index to to_index. More... | |
virtual int | numChildren () const |
Return the number of child objects (Property or otherwise). More... | |
virtual bool | paint (QPainter *painter, const QStyleOptionViewItem &option) const |
Hook to provide custom painting of the value data (right-hand column) in a subclass. More... | |
template<typename Func , typename P > | |
Property (const QString &name, const QVariant &default_value, const QString &description, P *parent, Func &&changed_slot) | |
template<typename Func , typename R > | |
Property (const QString &name, const QVariant &default_value, const QString &description, Property *parent, Func &&changed_slot, const R *receiver) | |
Property (const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr) | |
Constructor. More... | |
virtual void | removeChildren (int start_index=0, int count=-1) |
Remove and delete some or all child Properties. Does not change the value of this Property. More... | |
int | rowNumberInParent () const |
Return the row number of this property within its parent, or -1 if it has no parent. More... | |
virtual void | setDescription (const QString &description) |
Set the description. More... | |
virtual void | setHidden (bool hidden) |
Hide or show this property in any PropertyTreeWidget viewing its parent. More... | |
virtual void | setIcon (const QIcon &icon) |
Set the icon to be displayed next to the property. More... | |
void | setModel (PropertyTreeModel *model) |
Set the model managing this Property and all its child properties, recursively. More... | |
void | setParent (Property *new_parent) |
Set parent property, without telling the parent. More... | |
virtual void | setReadOnly (bool read_only) |
Prevent or allow users to edit this property from a PropertyTreeWidget. More... | |
void | setShouldBeSaved (bool save) |
If save is false, neither the property nor its children will get saved. If true (the default), the property itself will only get saved if it is not read-only; children will get saved in any case (according to their save + read-only flags). More... | |
virtual bool | setValue (const QVariant &new_value) |
Set the new value for this property. Returns true if the new value is different from the old value, false if same. More... | |
bool | shouldBeSaved () const |
Returns true if the property has data worth saving. More... | |
void | show () |
Show this Property in any PropertyTreeWidgets. More... | |
virtual Property * | subProp (const QString &sub_name) |
Return the first child Property with the given name, or the FailureProperty if no child has the name. More... | |
Property * | takeChild (Property *child) |
Remove a given child object and return a pointer to it. More... | |
virtual Property * | takeChildAt (int index) |
Take a child out of the child list, but don't destroy it. More... | |
~Property () override | |
Destructor. Removes this property from its parent's list of children. More... | |
Protected Member Functions | |
void | onInitialize () override |
Do initialization. Overridden from MessageFilterDisplay. More... | |
void | processMessage (const sensor_msgs::PointCloud2ConstPtr &cloud) override |
Process a single message. Overridden from MessageFilterDisplay. More... | |
Protected Member Functions inherited from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 > | |
void | fixedFrameChanged () override |
Called by setFixedFrame(). Override to respond to changes to fixed_frame_. More... | |
void | incomingMessage (const typename sensor_msgs::PointCloud2 ::ConstPtr &msg) |
Incoming message callback. Checks if the message pointer is valid, increments messages_received_, then calls processMessage(). More... | |
void | onDisable () override |
Derived classes override this to do the actual work of disabling themselves. More... | |
void | onEnable () override |
Derived classes override this to do the actual work of enabling themselves. More... | |
virtual void | processMessage (const typename sensor_msgs::PointCloud2 ::ConstPtr &msg)=0 |
Implement this to process the contents of a message. More... | |
void | processTypeErasedMessage (boost::shared_ptr< const void > type_erased_msg) override |
virtual void | subscribe () |
virtual void | unsubscribe () |
void | updateQueueSize () override |
void | updateTopic () override |
Protected Member Functions inherited from rviz::Display | |
virtual void | clearStatuses () |
Delete all status children. This is thread-safe. More... | |
bool | initialized () const |
Returns true if the display has been initialized. More... | |
Protected Member Functions inherited from rviz::Property | |
void | loadValue (const Config &config) |
Load the value of this property specifically, not including children. More... | |
Protected Attributes | |
PointCloudCommon * | point_cloud_common_ |
Protected Attributes inherited from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 > | |
uint32_t | messages_received_ |
message_filters::Subscriber< sensor_msgs::PointCloud2 > | sub_ |
tf2_ros::MessageFilter< sensor_msgs::PointCloud2 > * | tf_filter_ |
Protected Attributes inherited from rviz::_RosTopicDisplay | |
IntProperty * | queue_size_property_ |
RosTopicProperty * | topic_property_ |
BoolProperty * | unreliable_property_ |
Protected Attributes inherited from rviz::Display | |
DisplayContext * | context_ |
This DisplayContext pointer is the main connection a Display has into the rest of rviz. This is how the FrameManager is accessed, the SelectionManager, etc. When a Display subclass wants to signal that a new render should be done right away, call context_->queueRender(). More... | |
QString | fixed_frame_ |
A convenience variable equal to context_->getFixedFrame(). More... | |
Ogre::SceneManager * | scene_manager_ |
A convenience variable equal to context_->getSceneManager(). More... | |
Ogre::SceneNode * | scene_node_ |
The Ogre::SceneNode to hold all 3D scene elements shown by this Display. More... | |
ros::NodeHandle | threaded_nh_ |
A NodeHandle whose CallbackQueue is run from a different thread than the GUI. More... | |
ros::NodeHandle | update_nh_ |
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread). More... | |
Protected Attributes inherited from rviz::Property | |
bool | child_indexes_valid_ |
True if row_number_within_parent_ of all children is valid, false if not. More... | |
QIcon | icon_ |
PropertyTreeModel * | model_ |
Pointer to the PropertyTreeModel managing this property tree. More... | |
QVariant | value_ |
This is the central property value. If you set it directly in a subclass, do so with care because many things depend on the aboutToChange() and changed() events emitted by setValue(). More... | |
Additional Inherited Members | |
Public Types inherited from rviz::MessageFilterDisplay< sensor_msgs::PointCloud2 > | |
typedef MessageFilterDisplay< sensor_msgs::PointCloud2 > | MFDClass |
Convenience typedef so subclasses don't have to use the long templated class name to refer to their super class. More... | |
Public Slots inherited from rviz::Display | |
virtual void | onEnableChanged () |
void | queueRender () |
Convenience function which calls context_->queueRender(). More... | |
void | setEnabled (bool enabled) |
Enable or disable this Display. More... | |
void | setIcon (const QIcon &icon) override |
Set the Display's icon. More... | |
Public Slots inherited from rviz::BoolProperty | |
bool | setBool (bool value) |
Signals inherited from rviz::Display | |
void | timeSignal (ros::Time time, QPrivateSignal) |
Signals inherited from rviz::Property | |
void | aboutToChange () |
Emitted by setValue() just before the value has changed. More... | |
void | changed () |
Emitted by setValue() just after the value has changed. More... | |
void | childListChanged (Property *this_property) |
Emitted after insertions and deletions of child Properties. More... | |
Protected Slots inherited from rviz::_RosTopicDisplay |
Displays a point cloud of type sensor_msgs::PointCloud2.
By default it will assume channel 0 of the cloud is an intensity value, and will color them by intensity. If you set the channel's name to "rgb", it will interpret the channel as an integer rgb value, with r, g and b all being 8 bits.
Definition at line 52 of file point_cloud2_display.h.
rviz::PointCloud2Display::PointCloud2Display | ( | ) |
Definition at line 47 of file point_cloud2_display.cpp.
|
override |
Definition at line 51 of file point_cloud2_display.cpp.
|
overrideprotectedvirtual |
Do initialization. Overridden from MessageFilterDisplay.
Reimplemented from rviz::Display.
Definition at line 57 of file point_cloud2_display.cpp.
|
overrideprotected |
Process a single message. Overridden from MessageFilterDisplay.
Definition at line 66 of file point_cloud2_display.cpp.
|
overridevirtual |
Called to tell the display to clear its state.
Reimplemented from rviz::Display.
Definition at line 164 of file point_cloud2_display.cpp.
|
overridevirtual |
Called periodically by the visualization manager.
wall_dt | Wall-clock time, in seconds, since the last time the update list was run through. |
ros_dt | ROS time, in seconds, since the last time the update list was run through. |
Reimplemented from rviz::Display.
Definition at line 159 of file point_cloud2_display.cpp.
|
protected |
Definition at line 70 of file point_cloud2_display.h.