temperature_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
32 
33 #include <ros/time.h>
34 
37 #include <rviz/display_context.h>
38 #include <rviz/frame_manager.h>
41 #include <rviz/validate_floats.h>
42 
43 #include "temperature_display.h"
44 
45 namespace rviz
46 {
47 TemperatureDisplay::TemperatureDisplay() : point_cloud_common_(new PointCloudCommon(this))
48 {
49 }
50 
52 {
54  delete point_cloud_common_;
55 }
56 
58 {
59  // Use the threaded queue for processing of incoming messages
61 
64 
65  // Set correct initial values
66  subProp("Channel Name")->setValue("temperature");
67  subProp("Autocompute Intensity Bounds")->setValue(false);
68  subProp("Invert Rainbow")->setValue(true);
69  subProp("Min Intensity")->setValue(0); // Water Freezing
70  subProp("Max Intensity")->setValue(100); // Water Boiling
71 }
72 
73 void TemperatureDisplay::processMessage(const sensor_msgs::TemperatureConstPtr& msg)
74 {
75  sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
76 
77  // Create fields
78  sensor_msgs::PointField x;
79  x.name = "x";
80  x.offset = 0;
81  x.datatype = sensor_msgs::PointField::FLOAT32;
82  x.count = 1;
83  sensor_msgs::PointField y;
84  y.name = "y";
85  y.offset = 4;
86  y.datatype = sensor_msgs::PointField::FLOAT32;
87  y.count = 1;
88  sensor_msgs::PointField z;
89  z.name = "z";
90  z.offset = 8;
91  z.datatype = sensor_msgs::PointField::FLOAT32;
92  z.count = 1;
93  sensor_msgs::PointField temperature;
94  temperature.name = "temperature";
95  temperature.offset = 12;
96  temperature.datatype = sensor_msgs::PointField::FLOAT64;
97  temperature.count = 1;
98 
99  // Create pointcloud from message
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; // RelativeHumidity is always on its tf frame
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;
112  filtered->width = 1;
113  filtered->is_bigendian = false;
114  filtered->point_step = 20;
115  filtered->row_step = 1;
116 
117  // Give to point_cloud_common to draw
118  point_cloud_common_->addMessage(filtered);
119 }
120 
121 
122 void TemperatureDisplay::update(float wall_dt, float ros_dt)
123 {
124  point_cloud_common_->update(wall_dt, ros_dt);
125 
126  // Hide unneeded properties
127  subProp("Position Transformer")->hide();
128  subProp("Color Transformer")->hide();
129  subProp("Channel Name")->hide();
130  subProp("Invert Rainbow")->hide();
131  subProp("Autocompute Intensity Bounds")->hide();
132 }
133 
135 {
136  MFDClass::reset();
138 }
139 
140 } // namespace rviz
141 
rviz::MessageFilterDisplay< sensor_msgs::Temperature >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::MessageFilterDisplay< sensor_msgs::Temperature >::unsubscribe
virtual void unsubscribe()
Definition: message_filter_display.h:177
rviz::PointCloudCommon::initialize
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
Definition: point_cloud_common.cpp:366
rviz::PointCloudCommon::update
void update(float wall_dt, float ros_dt)
Definition: point_cloud_common.cpp:520
rviz::TemperatureDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition: temperature_display.cpp:122
time.h
rviz::TemperatureDisplay::onInitialize
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Definition: temperature_display.cpp:57
point_cloud_common.h
int_property.h
point_cloud.h
rviz::DisplayContext::getThreadedQueue
virtual ros::CallbackQueueInterface * getThreadedQueue()=0
Return a CallbackQueue using a different thread than the main GUI one.
rviz::Property::subProp
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.
Definition: property.cpp:179
rviz::PointCloudCommon::addMessage
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
Definition: point_cloud_common.cpp:939
rviz::TemperatureDisplay::~TemperatureDisplay
~TemperatureDisplay() override
Definition: temperature_display.cpp:51
rviz::Display
Definition: display.h:63
rviz::TemperatureDisplay
Displays a Temperature message of type sensor_msgs::Temperature.
Definition: temperature_display.h:48
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
rviz::TemperatureDisplay::processMessage
void processMessage(const sensor_msgs::TemperatureConstPtr &msg) override
Process a single message. Overridden from MessageFilterDisplay.
Definition: temperature_display.cpp:73
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::Property::setValue
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,...
Definition: property.cpp:134
rviz
Definition: add_display_dialog.cpp:54
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
point_cloud_transformers.h
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition: point_cloud_common.h:84
temperature_display.h
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::TemperatureDisplay::point_cloud_common_
PointCloudCommon * point_cloud_common_
Definition: temperature_display.h:66
rviz::MessageFilterDisplay< sensor_msgs::Temperature >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
rviz::TemperatureDisplay::TemperatureDisplay
TemperatureDisplay()
Definition: temperature_display.cpp:47
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
class_list_macros.hpp
rviz::TemperatureDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: temperature_display.cpp:134
rviz::PointCloudCommon::reset
void reset()
Definition: point_cloud_common.cpp:508
display_context.h
rviz::Display::update_nh_
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:300


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53