relative_humidity_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <OgreSceneNode.h>
00031 #include <OgreSceneManager.h>
00032 
00033 #include <ros/time.h>
00034 
00035 #include "rviz/default_plugin/point_cloud_common.h"
00036 #include "rviz/default_plugin/point_cloud_transformers.h"
00037 #include "rviz/display_context.h"
00038 #include "rviz/frame_manager.h"
00039 #include "rviz/ogre_helpers/point_cloud.h"
00040 #include "rviz/properties/int_property.h"
00041 #include "rviz/validate_floats.h"
00042 
00043 #include "relative_humidity_display.h"
00044 
00045 namespace rviz
00046 {
00047 
00048 RelativeHumidityDisplay::RelativeHumidityDisplay()
00049   : point_cloud_common_( new PointCloudCommon( this ))
00050 {
00051   queue_size_property_ = new IntProperty( "Queue Size", 10,
00052                                           "Advanced: set the size of the incoming RelativeHumidity message queue. "
00053                                           " Increasing this is useful if your incoming TF data is delayed significantly "
00054                                           "from your RelativeHumidity data, but it can greatly increase memory usage if the messages are big.",
00055                                           this, SLOT( updateQueueSize() ));
00056 
00057   // PointCloudCommon sets up a callback queue with a thread for each
00058   // instance.  Use that for processing incoming messages.
00059   update_nh_.setCallbackQueue( point_cloud_common_->getCallbackQueue() );
00060 }
00061 
00062 RelativeHumidityDisplay::~RelativeHumidityDisplay()
00063 {
00064   delete point_cloud_common_;
00065 }
00066 
00067 void RelativeHumidityDisplay::onInitialize()
00068 {
00069   MFDClass::onInitialize();
00070   point_cloud_common_->initialize( context_, scene_node_ );
00071 
00072   // Set correct initial values
00073   subProp("Channel Name")->setValue("relative_humidity");
00074   subProp("Autocompute Intensity Bounds")->setValue(false);
00075   subProp("Min Intensity")->setValue(0.0); // 0% relative humidity
00076   subProp("Max Intensity")->setValue(1.0); // 100% relative humidity
00077 }
00078 
00079 void RelativeHumidityDisplay::updateQueueSize()
00080 {
00081   tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00082 }
00083 
00084 void RelativeHumidityDisplay::processMessage( const sensor_msgs::RelativeHumidityConstPtr& msg )
00085 {
00086   sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
00087 
00088   // Create fields
00089   sensor_msgs::PointField x;
00090   x.name = "x";
00091   x.offset = 0;
00092   x.datatype = sensor_msgs::PointField::FLOAT32;
00093   x.count = 1;
00094   sensor_msgs::PointField y;
00095   y.name = "y";
00096   y.offset = 4;
00097   y.datatype = sensor_msgs::PointField::FLOAT32;
00098   y.count = 1;
00099   sensor_msgs::PointField z;
00100   z.name = "z";
00101   z.offset = 8;
00102   z.datatype = sensor_msgs::PointField::FLOAT32;
00103   z.count = 1;
00104   sensor_msgs::PointField relative_humidity;
00105   relative_humidity.name = "relative_humidity";
00106   relative_humidity.offset = 12;
00107   relative_humidity.datatype = sensor_msgs::PointField::FLOAT64;
00108   relative_humidity.count = 1;
00109 
00110   // Create pointcloud from message
00111   filtered->header = msg->header;
00112   filtered->fields.push_back(x);
00113   filtered->fields.push_back(y);
00114   filtered->fields.push_back(z);
00115   filtered->fields.push_back(relative_humidity);
00116   filtered->data.resize(20);
00117   const float zero_float = 0.0; // RelativeHumidity is always on its tf frame
00118   memcpy(&filtered->data[x.offset], &zero_float, 4);
00119   memcpy(&filtered->data[y.offset], &zero_float, 4);
00120   memcpy(&filtered->data[z.offset], &zero_float, 4);
00121   memcpy(&filtered->data[relative_humidity.offset], &msg->relative_humidity, 8);
00122   filtered->height = 1;
00123   filtered->width = 1;
00124   filtered->is_bigendian = false;
00125   filtered->point_step = 20;
00126   filtered->row_step = 1;
00127 
00128   // Give to point_cloud_common to draw
00129   point_cloud_common_->addMessage( filtered );
00130 }
00131 
00132 
00133 void RelativeHumidityDisplay::update( float wall_dt, float ros_dt )
00134 {
00135   point_cloud_common_->update( wall_dt, ros_dt );
00136 
00137   // Hide unneeded properties
00138   subProp("Position Transformer")->hide();
00139   subProp("Color Transformer")->hide();
00140   subProp("Channel Name")->hide();
00141   subProp("Autocompute Intensity Bounds")->hide();
00142 }
00143 
00144 void RelativeHumidityDisplay::reset()
00145 {
00146   MFDClass::reset();
00147   point_cloud_common_->reset();
00148 }
00149 
00150 } // namespace rviz
00151 
00152 #include <pluginlib/class_list_macros.h>
00153 PLUGINLIB_EXPORT_CLASS( rviz::RelativeHumidityDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:28