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 
49  : point_cloud_common_( new PointCloudCommon( this ))
50 {
51  queue_size_property_ = new IntProperty( "Queue Size", 10,
52  "Advanced: set the size of the incoming Temperature message queue. "
53  " Increasing this is useful if your incoming TF data is delayed significantly "
54  "from your Temperature data, but it can greatly increase memory usage if the messages are big.",
55  this, SLOT( updateQueueSize() ));
56 
57  // PointCloudCommon sets up a callback queue with a thread for each
58  // instance. Use that for processing incoming messages.
60 }
61 
63 {
64  delete point_cloud_common_;
65 }
66 
68 {
71 
72  // Set correct initial values
73  subProp("Channel Name")->setValue("temperature");
74  subProp("Autocompute Intensity Bounds")->setValue(false);
75  subProp("Invert Rainbow")->setValue(true);
76  subProp("Min Intensity")->setValue(0); // Water Freezing
77  subProp("Max Intensity")->setValue(100); // Water Boiling
78 }
79 
81 {
83 }
84 
85 void TemperatureDisplay::processMessage( const sensor_msgs::TemperatureConstPtr& msg )
86 {
87  sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
88 
89  // Create fields
90  sensor_msgs::PointField x;
91  x.name = "x";
92  x.offset = 0;
93  x.datatype = sensor_msgs::PointField::FLOAT32;
94  x.count = 1;
95  sensor_msgs::PointField y;
96  y.name = "y";
97  y.offset = 4;
98  y.datatype = sensor_msgs::PointField::FLOAT32;
99  y.count = 1;
100  sensor_msgs::PointField z;
101  z.name = "z";
102  z.offset = 8;
103  z.datatype = sensor_msgs::PointField::FLOAT32;
104  z.count = 1;
105  sensor_msgs::PointField temperature;
106  temperature.name = "temperature";
107  temperature.offset = 12;
108  temperature.datatype = sensor_msgs::PointField::FLOAT64;
109  temperature.count = 1;
110 
111  // Create pointcloud from message
112  filtered->header = msg->header;
113  filtered->fields.push_back(x);
114  filtered->fields.push_back(y);
115  filtered->fields.push_back(z);
116  filtered->fields.push_back(temperature);
117  filtered->data.resize(20);
118  const float zero_float = 0.0; // RelativeHumidity is always on its tf frame
119  memcpy(&filtered->data[x.offset], &zero_float, 4);
120  memcpy(&filtered->data[y.offset], &zero_float, 4);
121  memcpy(&filtered->data[z.offset], &zero_float, 4);
122  memcpy(&filtered->data[temperature.offset], &msg->temperature, 8);
123  filtered->height = 1;
124  filtered->width = 1;
125  filtered->is_bigendian = false;
126  filtered->point_step = 20;
127  filtered->row_step = 1;
128 
129  // Give to point_cloud_common to draw
130  point_cloud_common_->addMessage( filtered );
131 }
132 
133 
134 void TemperatureDisplay::update( float wall_dt, float ros_dt )
135 {
136  point_cloud_common_->update( wall_dt, ros_dt );
137 
138  // Hide unneeded properties
139  subProp("Position Transformer")->hide();
140  subProp("Color Transformer")->hide();
141  subProp("Channel Name")->hide();
142  subProp("Invert Rainbow")->hide();
143  subProp("Autocompute Intensity Bounds")->hide();
144 }
145 
147 {
148  MFDClass::reset();
150 }
151 
152 } // namespace rviz
153 
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:256
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:130
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:73
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:269
ros::CallbackQueueInterface * getCallbackQueue()
void initialize(DisplayContext *context, Ogre::SceneNode *scene_node)
virtual void reset()
Called to tell the display to clear its state.
tf::MessageFilter< sensor_msgs::Temperature > * tf_filter_
TFSIMD_FORCE_INLINE const tfScalar & y() const
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:38
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:264
Displays a point cloud of type sensor_msgs::PointCloud.
virtual void setQueueSize(uint32_t new_queue_size)
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:174
PointCloudCommon * point_cloud_common_
void addMessage(const sensor_msgs::PointCloudConstPtr &cloud)
void setCallbackQueue(CallbackQueueInterface *queue)
TFSIMD_FORCE_INLINE const tfScalar & x() const
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
TFSIMD_FORCE_INLINE const tfScalar & z() const
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
Displays a Temperature message of type sensor_msgs::Temperature.
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:371
virtual void processMessage(const sensor_msgs::TemperatureConstPtr &msg)
Process a single message. Overridden from MessageFilterDisplay.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update(float wall_dt, float ros_dt)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:42