Go to the documentation of this file.
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
77 sensor_msgs::PointCloud2Ptr filtered(
new sensor_msgs::PointCloud2);
80 sensor_msgs::PointField x;
83 x.datatype = sensor_msgs::PointField::FLOAT32;
85 sensor_msgs::PointField y;
88 y.datatype = sensor_msgs::PointField::FLOAT32;
90 sensor_msgs::PointField z;
93 z.datatype = sensor_msgs::PointField::FLOAT32;
95 sensor_msgs::PointField illuminance;
96 illuminance.name =
"illuminance";
97 illuminance.offset = 12;
98 illuminance.datatype = sensor_msgs::PointField::FLOAT64;
99 illuminance.count = 1;
102 filtered->header = msg->header;
103 filtered->fields.push_back(x);
104 filtered->fields.push_back(y);
105 filtered->fields.push_back(z);
106 filtered->fields.push_back(illuminance);
107 filtered->data.resize(20);
108 const float zero_float = 0.0;
109 memcpy(&filtered->data[x.offset], &zero_float, 4);
110 memcpy(&filtered->data[y.offset], &zero_float, 4);
111 memcpy(&filtered->data[z.offset], &zero_float, 4);
112 memcpy(&filtered->data[illuminance.offset], &msg->illuminance, 8);
113 filtered->height = 1;
115 filtered->is_bigendian =
false;
116 filtered->point_step = 20;
117 filtered->row_step = 1;
virtual void unsubscribe()
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
void update(float wall_dt, float ros_dt)
void processMessage(const sensor_msgs::IlluminanceConstPtr &msg) override
Process a single message. Overridden from MessageFilterDisplay.
void reset() override
Called to tell the display to clear its state.
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
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.
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
void hide()
Hide this Property in any PropertyTreeWidgets.
~IlluminanceDisplay() override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
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,...
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Displays a point cloud of type sensor_msgs::PointCloud.
Displays an Illuminance message of type sensor_msgs::Illuminance.
void setCallbackQueue(CallbackQueueInterface *queue)
void onInitialize() override
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
PointCloudCommon * point_cloud_common_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09