property_test.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 <stdio.h>
00031 
00032 #include <gtest/gtest.h>
00033 
00034 #include <rviz/properties/property.h>
00035 #include <rviz/properties/color_property.h>
00036 #include <rviz/properties/vector_property.h>
00037 #include <rviz/properties/quaternion_property.h>
00038 #include <rviz/properties/enum_property.h>
00039 
00040 #include "mock_property_change_receiver.h"
00041 
00042 using namespace rviz;
00043 
00044 TEST( Property, name )
00045 {
00046   Property p;
00047   p.setName( "chub" );
00048   EXPECT_EQ( "chub", p.getName().toStdString() );
00049 }
00050 
00051 TEST( Property, description )
00052 {
00053   Property p;
00054   p.setDescription( "chub" );
00055   EXPECT_EQ( "chub", p.getDescription().toStdString() );
00056 }
00057 
00058 TEST( Property, value )
00059 {
00060   Property p;
00061   p.setValue( 199 );
00062   EXPECT_EQ( 199, p.getValue().toInt() );
00063 }
00064 
00065 TEST( Property, set_value_events )
00066 {
00067   Property p;
00068   p.setValue( 0 );
00069 
00070   MockPropertyChangeReceiver r( &p );
00071   p.connect( &p, SIGNAL( aboutToChange() ), &r, SLOT( aboutToChange() ));
00072   p.connect( &p, SIGNAL( changed() ), &r, SLOT( changed() ));
00073 
00074   p.setValue( 17 );
00075   EXPECT_EQ( " aboutToChange, v=0 changed, v=17", r.result().toStdString() );
00076 }
00077 
00078 TEST( Property, children )
00079 {
00080   Property* display = new Property( "Test" );
00081   new Property( "Alpha", 0.5, "The amount of transparency to apply to the grid lines.", display );
00082   Property* beta = new Property( "Beta Band", 10, "The number of betas to apply to the grid lines.", display );
00083   new Property( "Gamma Topic", "chubby", "The topic on which to listen for Gamma messages.", display );
00084   Property* position = new Property( "Position", QVariant(), "Position of the chub.", display );
00085   new Property( "X", 1.1f, "X component of the position of the chub.", position );
00086   new Property( "Y", 0.717f, "Y component of the position of the chub.", position );
00087 
00088   // Sample usage inside the Display which owns the property.
00089   int b = beta->getValue().toInt();
00090   EXPECT_EQ( 10, b );
00091 
00092   // Sample usage outside the Display
00093   beta->setValue( 12 );
00094   EXPECT_EQ( 12, display->subProp( "Beta Band" )->getValue().toInt() );
00095 
00096   // Compound property
00097   float y = display->subProp( "Position" )->subProp( "Y" )->getValue().toFloat();
00098   EXPECT_EQ( 0.717f, y );
00099 
00100   // Accessing a missing property should not crash.
00101   printf( "Next line should say 'ERROR' but not crash.\n" );
00102   display->subProp( "Position" )->subProp( "Z" )->getValue().toFloat();
00103 }
00104 
00105 TEST( VectorProperty, default_value )
00106 {
00107   VectorProperty* vp = new VectorProperty();
00108   Ogre::Vector3 vec = vp->getVector();
00109   EXPECT_EQ( 0, vec.x );
00110   EXPECT_EQ( 0, vec.y );
00111   EXPECT_EQ( 0, vec.z );
00112 }
00113 
00114 TEST( VectorProperty, set_and_get )
00115 {
00116   VectorProperty* vp = new VectorProperty();
00117   Ogre::Vector3 vec( 1, 2, 3 );
00118   vp->setVector( vec );
00119 
00120   Ogre::Vector3 vec2 = vp->getVector();
00121   EXPECT_EQ( 1, vec2.x );
00122   EXPECT_EQ( 2, vec2.y );
00123   EXPECT_EQ( 3, vec2.z );
00124 }
00125 
00126 TEST( VectorProperty, set_string )
00127 {
00128   VectorProperty* vp = new VectorProperty();
00129   vp->setValue( QString( "1;2;3" ));
00130 
00131   Ogre::Vector3 vec = vp->getVector();
00132   EXPECT_EQ( 1, vec.x );
00133   EXPECT_EQ( 2, vec.y );
00134   EXPECT_EQ( 3, vec.z );
00135 
00136   vp->setValue( QString( "chubby!" ));
00137 
00138   vec = vp->getVector();
00139   EXPECT_EQ( 1, vec.x );
00140   EXPECT_EQ( 2, vec.y );
00141   EXPECT_EQ( 3, vec.z );
00142 }
00143 
00144 TEST( VectorProperty, set_child )
00145 {
00146   VectorProperty* vp = new VectorProperty();
00147   vp->subProp( "X" )->setValue( 0.9 );
00148   vp->subProp( "Y" )->setValue( 1.1 );
00149   vp->subProp( "Z" )->setValue( 1.3 );
00150 
00151   Ogre::Vector3 vec = vp->getVector();
00152   EXPECT_EQ( 0.9f, vec.x );
00153   EXPECT_EQ( 1.1f, vec.y );
00154   EXPECT_EQ( 1.3f, vec.z );
00155 }
00156 
00157 TEST( VectorProperty, get_child )
00158 {
00159   VectorProperty* vp = new VectorProperty( "v", Ogre::Vector3( 1, 2, 3 ));
00160   EXPECT_EQ( 1, vp->subProp( "X" )->getValue().toFloat() );
00161   EXPECT_EQ( 2, vp->subProp( "Y" )->getValue().toFloat() );
00162   EXPECT_EQ( 3, vp->subProp( "Z" )->getValue().toFloat() );
00163 }
00164 
00165 TEST( VectorProperty, set_value_events )
00166 {
00167   VectorProperty p;
00168 
00169   MockPropertyChangeReceiver r( &p );
00170   p.connect( &p, SIGNAL( aboutToChange() ), &r, SLOT( aboutToChange() ));
00171   p.connect( &p, SIGNAL( changed() ), &r, SLOT( changed() ));
00172 
00173   p.setVector( Ogre::Vector3( .1, .0001, 1000 ));
00174   EXPECT_EQ( " aboutToChange, v=0; 0; 0 changed, v=0.1; 0.0001; 1000", r.result().toStdString() );
00175   r.reset();
00176 
00177   p.subProp( "Z" )->setValue( 2.1 );
00178   EXPECT_EQ( " aboutToChange, v=0.1; 0.0001; 1000 changed, v=0.1; 0.0001; 2.1", r.result().toStdString() );
00179 }
00180 
00181 TEST( QuaternionProperty, default_value )
00182 {
00183   QuaternionProperty* qp = new QuaternionProperty();
00184   Ogre::Quaternion quat = qp->getQuaternion();
00185   EXPECT_EQ( 0, quat.x );
00186   EXPECT_EQ( 0, quat.y );
00187   EXPECT_EQ( 0, quat.z );
00188   EXPECT_EQ( 1, quat.w );
00189 }
00190 
00191 TEST( QuaternionProperty, set_and_get )
00192 {
00193   QuaternionProperty* qp = new QuaternionProperty();
00194   Ogre::Quaternion quat( 4, 1, 2, 3 );
00195   qp->setQuaternion( quat );
00196 
00197   Ogre::Quaternion quat2 = qp->getQuaternion();
00198   EXPECT_EQ( 1, quat2.x );
00199   EXPECT_EQ( 2, quat2.y );
00200   EXPECT_EQ( 3, quat2.z );
00201   EXPECT_EQ( 4, quat2.w );
00202 }
00203 
00204 TEST( QuaternionProperty, set_string )
00205 {
00206   QuaternionProperty* qp = new QuaternionProperty();
00207   qp->setValue( QString( "1;2;3;4" ));
00208 
00209   Ogre::Quaternion quat = qp->getQuaternion();
00210   EXPECT_EQ( 1, quat.x );
00211   EXPECT_EQ( 2, quat.y );
00212   EXPECT_EQ( 3, quat.z );
00213   EXPECT_EQ( 4, quat.w );
00214 
00215   qp->setValue( QString( "chubby!" ));
00216 
00217   quat = qp->getQuaternion();
00218   EXPECT_EQ( 1, quat.x );
00219   EXPECT_EQ( 2, quat.y );
00220   EXPECT_EQ( 3, quat.z );
00221   EXPECT_EQ( 4, quat.w );
00222 }
00223 
00224 TEST( QuaternionProperty, set_child )
00225 {
00226   QuaternionProperty* qp = new QuaternionProperty();
00227   qp->subProp( "X" )->setValue( 0.9 );
00228   qp->subProp( "Y" )->setValue( 1.1 );
00229   qp->subProp( "Z" )->setValue( 1.3 );
00230   qp->subProp( "W" )->setValue( 1.5 );
00231 
00232   Ogre::Quaternion quat = qp->getQuaternion();
00233   EXPECT_EQ( 0.9f, quat.x );
00234   EXPECT_EQ( 1.1f, quat.y );
00235   EXPECT_EQ( 1.3f, quat.z );
00236   EXPECT_EQ( 1.5f, quat.w );
00237 }
00238 
00239 TEST( QuaternionProperty, get_child )
00240 {
00241   QuaternionProperty* qp = new QuaternionProperty( "v", Ogre::Quaternion( 4, 1, 2, 3 ));
00242   EXPECT_EQ( 1, qp->subProp( "X" )->getValue().toFloat() );
00243   EXPECT_EQ( 2, qp->subProp( "Y" )->getValue().toFloat() );
00244   EXPECT_EQ( 3, qp->subProp( "Z" )->getValue().toFloat() );
00245   EXPECT_EQ( 4, qp->subProp( "W" )->getValue().toFloat() );
00246 }
00247 
00248 TEST( QuaternionProperty, set_value_events )
00249 {
00250   QuaternionProperty p;
00251 
00252   MockPropertyChangeReceiver r( &p );
00253   p.connect( &p, SIGNAL( aboutToChange() ), &r, SLOT( aboutToChange() ));
00254   p.connect( &p, SIGNAL( changed() ), &r, SLOT( changed() ));
00255 
00256   p.setQuaternion( Ogre::Quaternion( 1, .1, .0001, 1000 ));
00257   EXPECT_EQ( " aboutToChange, v=0; 0; 0; 1 changed, v=0.1; 0.0001; 1000; 1", r.result().toStdString() );
00258   r.reset();
00259 
00260   p.subProp( "Z" )->setValue( 2.1 );
00261   EXPECT_EQ( " aboutToChange, v=0.1; 0.0001; 1000; 1 changed, v=0.1; 0.0001; 2.1; 1", r.result().toStdString() );
00262 }
00263 
00264 TEST( ColorProperty, default_value )
00265 {
00266   ColorProperty* qp = new ColorProperty();
00267   QColor color = qp->getColor();
00268   EXPECT_EQ( 0, color.red() );
00269   EXPECT_EQ( 0, color.green() );
00270   EXPECT_EQ( 0, color.blue() );
00271 }
00272 
00273 TEST( ColorProperty, set_and_get )
00274 {
00275   ColorProperty* qp = new ColorProperty();
00276   QColor color( 1, 2, 3 );
00277   qp->setColor( color );
00278 
00279   QColor color2 = qp->getColor();
00280   EXPECT_EQ( 1, color2.red() );
00281   EXPECT_EQ( 2, color2.green() );
00282   EXPECT_EQ( 3, color2.blue() );
00283 }
00284 
00285 TEST( ColorProperty, set_string )
00286 {
00287   ColorProperty* qp = new ColorProperty();
00288   qp->setValue( QString( "1;2;3" ));
00289 
00290   QColor color = qp->getColor();
00291   EXPECT_EQ( 1, color.red() );
00292   EXPECT_EQ( 2, color.green() );
00293   EXPECT_EQ( 3, color.blue() );
00294 
00295   qp->setValue( QString( "chubby!" ));
00296 
00297   color = qp->getColor();
00298   EXPECT_EQ( 1, color.red() );
00299   EXPECT_EQ( 2, color.green() );
00300   EXPECT_EQ( 3, color.blue() );
00301 }
00302 
00303 TEST( ColorProperty, set_string_limits )
00304 {
00305   ColorProperty* qp = new ColorProperty();
00306   qp->setValue( QString( "-1;2000;3" ));
00307 
00308   QColor color = qp->getColor();
00309   EXPECT_EQ( 0, color.red() );
00310   EXPECT_EQ( 255, color.green() );
00311   EXPECT_EQ( 3, color.blue() );
00312 }
00313 
00314 TEST( ColorProperty, set_value_events )
00315 {
00316   ColorProperty p;
00317 
00318   MockPropertyChangeReceiver r( &p );
00319   p.connect( &p, SIGNAL( aboutToChange() ), &r, SLOT( aboutToChange() ));
00320   p.connect( &p, SIGNAL( changed() ), &r, SLOT( changed() ));
00321 
00322   p.setColor( QColor( 1, 2, 3 ));
00323   EXPECT_EQ( " aboutToChange, v=0; 0; 0 changed, v=1; 2; 3", r.result().toStdString() );
00324 }
00325 
00326 TEST( EnumProperty, basic )
00327 {
00328   EnumProperty p;
00329 
00330   EXPECT_EQ( 0, p.getOptionInt() );
00331 
00332   p.addOption( "chub", 10 );
00333   EXPECT_EQ( 0, p.getOptionInt() );
00334 
00335   p.addOption( "foo", 3 );
00336   p.addOption( "bar", 999 );
00337 
00338   p.setValue( "chub" );
00339   EXPECT_EQ( 10, p.getOptionInt() );
00340 
00341   p.clearOptions();
00342   EXPECT_EQ( 0, p.getOptionInt() );
00343 }
00344 
00345 int main( int argc, char **argv ) {
00346   testing::InitGoogleTest( &argc, argv );
00347   return RUN_ALL_TESTS();
00348 }


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