Go to the documentation of this file.
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
75 sensor_msgs::PointCloud2Ptr filtered(
new sensor_msgs::PointCloud2);
78 sensor_msgs::PointField x;
81 x.datatype = sensor_msgs::PointField::FLOAT32;
83 sensor_msgs::PointField y;
86 y.datatype = sensor_msgs::PointField::FLOAT32;
88 sensor_msgs::PointField z;
91 z.datatype = sensor_msgs::PointField::FLOAT32;
93 sensor_msgs::PointField temperature;
94 temperature.name =
"temperature";
95 temperature.offset = 12;
96 temperature.datatype = sensor_msgs::PointField::FLOAT64;
97 temperature.count = 1;
100 filtered->header = msg->header;
101 filtered->fields.push_back(x);
102 filtered->fields.push_back(y);
103 filtered->fields.push_back(z);
104 filtered->fields.push_back(temperature);
105 filtered->data.resize(20);
106 const float zero_float = 0.0;
107 memcpy(&filtered->data[x.offset], &zero_float, 4);
108 memcpy(&filtered->data[y.offset], &zero_float, 4);
109 memcpy(&filtered->data[z.offset], &zero_float, 4);
110 memcpy(&filtered->data[temperature.offset], &msg->temperature, 8);
111 filtered->height = 1;
113 filtered->is_bigendian =
false;
114 filtered->point_step = 20;
115 filtered->row_step = 1;
virtual void unsubscribe()
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
void update(float wall_dt, float ros_dt)
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
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)
~TemperatureDisplay() override
Displays a Temperature message of type sensor_msgs::Temperature.
void hide()
Hide this Property in any PropertyTreeWidgets.
void processMessage(const sensor_msgs::TemperatureConstPtr &msg) override
Process a single message. Overridden from MessageFilterDisplay.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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.
Displays a point cloud of type sensor_msgs::PointCloud.
void setCallbackQueue(CallbackQueueInterface *queue)
PointCloudCommon * point_cloud_common_
void onInitialize() override
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
void reset() override
Called to tell the display to clear its state.
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10