illuminance_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 "illuminance_display.h"
44 
45 namespace rviz
46 {
47 IlluminanceDisplay::IlluminanceDisplay() : 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("illuminance");
67  subProp("Autocompute Intensity Bounds")->setValue(false);
68  subProp("Min Intensity")->setValue(0);
69  subProp("Max Intensity")->setValue(1000);
70 }
71 
72 void IlluminanceDisplay::processMessage(const sensor_msgs::IlluminanceConstPtr& msg)
73 {
74  // Filter any nan values out of the cloud. Any nan values that make it through to PointCloudBase
75  // will get their points put off in lala land, but it means they still do get processed/rendered
76  // which can be a big performance hit
77  sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
78 
79  // Create fields
80  sensor_msgs::PointField x;
81  x.name = "x";
82  x.offset = 0;
83  x.datatype = sensor_msgs::PointField::FLOAT32;
84  x.count = 1;
85  sensor_msgs::PointField y;
86  y.name = "y";
87  y.offset = 4;
88  y.datatype = sensor_msgs::PointField::FLOAT32;
89  y.count = 1;
90  sensor_msgs::PointField z;
91  z.name = "z";
92  z.offset = 8;
93  z.datatype = sensor_msgs::PointField::FLOAT32;
94  z.count = 1;
95  sensor_msgs::PointField illuminance;
96  illuminance.name = "illuminance";
97  illuminance.offset = 12;
98  illuminance.datatype = sensor_msgs::PointField::FLOAT64;
99  illuminance.count = 1;
100 
101  // Create pointcloud from message
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; // Illuminance is always on its tf frame
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;
114  filtered->width = 1;
115  filtered->is_bigendian = false;
116  filtered->point_step = 20;
117  filtered->row_step = 1;
118 
119  // Give to point_cloud_common to draw
120  point_cloud_common_->addMessage(filtered);
121 }
122 
123 
124 void IlluminanceDisplay::update(float wall_dt, float ros_dt)
125 {
126  point_cloud_common_->update(wall_dt, ros_dt);
127 
128  // Hide unneeded properties
129  subProp("Position Transformer")->hide();
130  subProp("Color Transformer")->hide();
131  subProp("Channel Name")->hide();
132  subProp("Autocompute Intensity Bounds")->hide();
133 }
134 
136 {
137  MFDClass::reset();
139 }
140 
141 } // namespace rviz
142 
rviz::MessageFilterDisplay< sensor_msgs::Illuminance >::reset
void reset() override
Definition: message_filter_display.h:125
validate_floats.h
frame_manager.h
rviz::MessageFilterDisplay< sensor_msgs::Illuminance >::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::IlluminanceDisplay::processMessage
void processMessage(const sensor_msgs::IlluminanceConstPtr &msg) override
Process a single message. Overridden from MessageFilterDisplay.
Definition: illuminance_display.cpp:72
time.h
point_cloud_common.h
int_property.h
rviz::IlluminanceDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: illuminance_display.cpp:135
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::Display
Definition: display.h:63
rviz::Property::hide
void hide()
Hide this Property in any PropertyTreeWidgets.
Definition: property.h:462
rviz::IlluminanceDisplay::~IlluminanceDisplay
~IlluminanceDisplay() override
Definition: illuminance_display.cpp:51
illuminance_display.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::IlluminanceDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition: illuminance_display.cpp:124
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::IlluminanceDisplay::onInitialize
void onInitialize() override
Do initialization. Overridden from MessageFilterDisplay.
Definition: illuminance_display.cpp:57
rviz::PointCloudCommon
Displays a point cloud of type sensor_msgs::PointCloud.
Definition: point_cloud_common.h:84
rviz::IlluminanceDisplay
Displays an Illuminance message of type sensor_msgs::Illuminance.
Definition: illuminance_display.h:48
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::MessageFilterDisplay< sensor_msgs::Illuminance >::onInitialize
void onInitialize() override
Definition: message_filter_display.h:105
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::PointCloudCommon::reset
void reset()
Definition: point_cloud_common.cpp:508
display_context.h
rviz::IlluminanceDisplay::IlluminanceDisplay
IlluminanceDisplay()
Definition: illuminance_display.cpp:47
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::IlluminanceDisplay::point_cloud_common_
PointCloudCommon * point_cloud_common_
Definition: illuminance_display.h:66


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02