property_test.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, 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 <QtGui/QApplication>
00031 
00032 #include <OGRE/OgreVector3.h>
00033 
00034 #include "ros/ros.h"
00035 
00036 #include "rviz/properties/property_manager.h"
00037 #include "rviz/properties/property.h"
00038 #include "rviz/properties/property_tree_widget.h"
00039 #include "rviz/properties/property_tree_with_help.h"
00040 #include "rviz/frame_manager.h"
00041 #include "ros_spinner.h"
00042 
00043 using namespace rviz;
00044 
00045 PropertyManager* pm;
00046 
00047 class MyPropertyReceiver
00048 {
00049 private:
00050   bool b_;
00051   int i_;
00052   int e_;
00053   float f_;
00054   std::string s_;
00055   std::string t_;
00056   std::string ee_;
00057   std::string tf_;
00058   int index_;
00059   StatusPropertyPtr sp_;
00060   Color c_;
00061   Ogre::Vector3 v_;
00062   Ogre::Quaternion q_;
00063 
00064 public:
00065   MyPropertyReceiver( int index ): index_( index ) {}
00066   void setBool( bool value ) {
00067     b_ = value;
00068     printf("%d bool = %s\n", index_, b_?"true":"false");
00069     if( !b_ && sp_ ) {
00070       sp_->deleteStatus( "Bread" );
00071       pm->update();
00072     }
00073   }
00074   void setColor( Color value ) { c_ = value; printf("%d color = %.3f, %.3f, %.3f\n", index_, c_.r_, c_.g_, c_.b_); }
00075   void setInt( int value ) { i_ = value; printf("%d int = %d\n", index_, i_); }
00076   void setEnum( int value ) { e_ = value; printf("%d enum = %d\n", index_, e_); }
00077   void setFloat( float value ) { f_ = value; printf("%d float = %f\n", index_, f_); }
00078   void setString( std::string value ) { s_ = value; printf("%d string = %s\n", index_, s_.c_str()); }
00079   void setEE( std::string value ) { ee_ = value; printf("%d edit enum = %s\n", index_, ee_.c_str()); }
00080   void setTF( std::string value ) { tf_ = value; printf("%d tf frame = %s\n", index_, tf_.c_str()); }
00081   void setTopic( std::string value ) { t_ = value; printf("%d topic = %s\n", index_, t_.c_str()); }
00082   void setVector3( Ogre::Vector3 value ) { v_ = value; printf("%d vector3 = %f, %f, %f\n", index_, v_.x, v_.y, v_.z); }
00083   void setQuaternion( Ogre::Quaternion value ) { q_ = value; printf("%d quaternion = %f, %f, %f, %f\n", index_, q_.x, q_.y, q_.z, q_.w); }
00084 
00085   bool getBool() { return b_; }
00086   Color getColor() { return c_; }
00087   int getInt() { return i_; }
00088   int getEnum() { return e_; }
00089   float getFloat() { return f_; }
00090   std::string getString() { return s_; }
00091   std::string getEE() { return ee_; }
00092   std::string getTF() { return tf_; }
00093   std::string getTopic() { return t_; }
00094   Ogre::Vector3 getVector3() { return v_; }
00095   Ogre::Quaternion getQuaternion() { return q_; }
00096 
00097   void setStatusProperty( StatusPropertyPtr sp ) { sp_ = sp; }
00098 
00099   void optionCallback( V_string& options_out )
00100   {
00101     options_out.push_back( "Callee Pays" );
00102     options_out.push_back( "Caller Pays" );
00103     options_out.push_back( "Phone Company Pays" );
00104     options_out.push_back( "Taxpayers Pay" );
00105   }
00106 };
00107 
00108 int main(int argc, char **argv)
00109 {
00110   ros::init( argc, argv, "property_test" );
00111 
00112   FrameManagerPtr frame_manager = FrameManager::instance();
00113 
00114   QApplication app(argc, argv);
00115 
00116   RosSpinner spinner;
00117 
00118   MyPropertyReceiver recvr( 1 );
00119   MyPropertyReceiver recvr2( 2 );
00120   MyPropertyReceiver recvr3( 3 );
00121 
00122   pm = new PropertyManager();
00123   {
00124     CategoryPropertyWPtr options_category = pm->createCategory( ".Global Options", "",
00125                                                                 CategoryPropertyWPtr(), NULL );
00126     BoolPropertyWPtr bool_prop =
00127       pm->createProperty<BoolProperty>( "Lumpy", "",
00128                                         boost::bind( &MyPropertyReceiver::getBool, &recvr ),
00129                                         boost::bind( &MyPropertyReceiver::setBool, &recvr, _1 ),
00130                                         options_category, NULL );
00131     setPropertyHelpText(bool_prop, "A sample boolean property.");
00132     BoolPropertyPtr bp = bool_prop.lock();
00133     bp->set( true );
00134 
00135     StringPropertyWPtr string_prop =
00136       pm->createProperty<StringProperty>( "Style", "",
00137                                           boost::bind( &MyPropertyReceiver::getString, &recvr ),
00138                                           boost::bind( &MyPropertyReceiver::setString, &recvr, _1 ),
00139                                           options_category, NULL );
00140     setPropertyHelpText(string_prop, "A sample stringean property.");
00141     StringPropertyPtr sp = string_prop.lock();
00142     sp->set( "nubby" );
00143 
00144     ColorPropertyWPtr color_prop =
00145       pm->createProperty<ColorProperty>( "Cheese Color", "",
00146                                           boost::bind( &MyPropertyReceiver::getColor, &recvr ),
00147                                           boost::bind( &MyPropertyReceiver::setColor, &recvr, _1 ),
00148                                           options_category, NULL );
00149     setPropertyHelpText(color_prop, "A sample color property.");
00150     ColorPropertyPtr cp = color_prop.lock();
00151     cp->set( Color( .1f, .4f, 1.0f ));
00152 
00153     EnumPropertyWPtr enum_prop =
00154       pm->createProperty<EnumProperty>( "Cheese Enum", "",
00155                                         boost::bind( &MyPropertyReceiver::getEnum, &recvr ),
00156                                         boost::bind( &MyPropertyReceiver::setEnum, &recvr, _1 ),
00157                                         options_category, NULL );
00158     setPropertyHelpText(enum_prop, "A sample enum property.");
00159     EnumPropertyPtr ep = enum_prop.lock();
00160     ep->addOption( "cheddar", 6 );
00161     ep->addOption( "swiss", 7 );
00162     ep->addOption( "Humboldt Fog", 99 );
00163     ep->addOption( "chester", -1 );
00164     ep->addOption( "blubber", 0 );
00165     ep->set( 7 );
00166 
00167     TFFramePropertyWPtr tf_prop =
00168       pm->createProperty<TFFrameProperty>( "Picture Frame", "",
00169                                            boost::bind( &MyPropertyReceiver::getTF, &recvr ),
00170                                            boost::bind( &MyPropertyReceiver::setTF, &recvr, _1 ),
00171                                            options_category, NULL );
00172     setPropertyHelpText(tf_prop, "A sample tf frame property.");
00173     TFFramePropertyPtr tfp = tf_prop.lock();
00174     tfp->set( "base_link" );
00175 
00176     EditEnumPropertyWPtr ee_prop =
00177       pm->createProperty<EditEnumProperty>( "Chub Enum", "",
00178                                             boost::bind( &MyPropertyReceiver::getEE, &recvr ),
00179                                             boost::bind( &MyPropertyReceiver::setEE, &recvr, _1 ),
00180                                             options_category, NULL );
00181     setPropertyHelpText(ee_prop, "A sample editable enum property.");
00182     EditEnumPropertyPtr eep = ee_prop.lock();
00183     eep->addOption( "Tubby" );
00184     eep->addOption( "Portly" );
00185     eep->addOption( "Chunky" );
00186     eep->addOption( "Chunkstyle" );
00187     eep->addOption( "Round" );
00188     eep->set( "Portly" );
00189 
00190     IntPropertyWPtr int_prop =
00191       pm->createProperty<IntProperty>( "Planet Number", "",
00192                                        boost::bind( &MyPropertyReceiver::getInt, &recvr2 ),
00193                                        boost::bind( &MyPropertyReceiver::setInt, &recvr2, _1 ),
00194                                        options_category, NULL );
00195     setPropertyHelpText(int_prop, "The number of the planet, from Mercury (1) to Pluto (9)  For more information, see <a href=\"http://en.wikipedia.org/wiki/Solar_System\">The Solar System</a>.");
00196     IntPropertyPtr ip = int_prop.lock();
00197     ip->set( 3 );
00198     ip->setMax( 9 );
00199     ip->setMin( 1 );
00200 
00201     FloatPropertyWPtr float_prop =
00202       pm->createProperty<FloatProperty>( "Alpha", "",
00203                                          boost::bind( &MyPropertyReceiver::getFloat, &recvr2 ),
00204                                          boost::bind( &MyPropertyReceiver::setFloat, &recvr2, _1 ),
00205                                          options_category, NULL );
00206     setPropertyHelpText(float_prop, "Opacity.");
00207     FloatPropertyPtr fp = float_prop.lock();
00208     fp->set( 0.5 );
00209     fp->setMax( 1.0 );
00210     fp->setMin( 0 );
00211   }
00212   {
00213     CategoryPropertyWPtr options_category = pm->createCheckboxCategory( "Pedestrian", "", "",
00214                                                                         boost::bind( &MyPropertyReceiver::getBool, &recvr2 ),
00215                                                                         boost::bind( &MyPropertyReceiver::setBool, &recvr2, _1 ));
00216     StatusPropertyWPtr stat_prop = pm->createStatus( "Options Status", "prop_prefix", options_category );
00217     {
00218       StatusPropertyPtr sp = stat_prop.lock();
00219       sp->setStatus( status_levels::Error, "Bread", "moldy" );
00220       sp->setStatus( status_levels::Ok, "Orange Juice", "tasty" );
00221       sp->setStatus( status_levels::Warn, "Cheese", "hard and crusty" );
00222       sp->setStatus( status_levels::Warn, "Lemons", "too tangy" );
00223       recvr.setStatusProperty( sp );
00224     }
00225     ROSTopicStringPropertyWPtr topic_prop =
00226       pm->createProperty<ROSTopicStringProperty>( "Topic", "",
00227                                                   boost::bind( &MyPropertyReceiver::getTopic, &recvr3 ),
00228                                                   boost::bind( &MyPropertyReceiver::setTopic, &recvr3, _1 ),
00229                                                   options_category, NULL );
00230     setPropertyHelpText(topic_prop, "What topic to listen to.");
00231     ROSTopicStringPropertyPtr tp = topic_prop.lock();
00232     tp->setMessageType( "std_msgs/String" );
00233     tp->set( "chatter" );
00234 
00235     BoolPropertyWPtr bool_prop =
00236       pm->createProperty<BoolProperty>( "Active", "",
00237                                         boost::bind( &MyPropertyReceiver::getBool, &recvr3 ),
00238                                         boost::bind( &MyPropertyReceiver::setBool, &recvr3, _1 ),
00239                                         options_category, NULL );
00240     setPropertyHelpText(bool_prop, "A sample boolean property.");
00241     BoolPropertyPtr bp = bool_prop.lock();
00242     bp->set( true );
00243 
00244     StringPropertyWPtr string_prop =
00245       pm->createProperty<StringProperty>( "Cheese type", "",
00246                                           boost::bind( &MyPropertyReceiver::getString, &recvr3 ),
00247                                           boost::bind( &MyPropertyReceiver::setString, &recvr3, _1 ),
00248                                           options_category, NULL );
00249     setPropertyHelpText(string_prop, "A sample stringean property.");
00250     StringPropertyPtr sp = string_prop.lock();
00251     sp->set( "nubby" );
00252 
00253     IntPropertyWPtr int_prop =
00254       pm->createProperty<IntProperty>( "NumLemons", "",
00255                                        boost::bind( &MyPropertyReceiver::getInt, &recvr3 ),
00256                                        boost::bind( &MyPropertyReceiver::setInt, &recvr3, _1 ),
00257                                        options_category, NULL );
00258     setPropertyHelpText(int_prop, "Number of lemons in a basket.");
00259     IntPropertyPtr ip = int_prop.lock();
00260     ip->set( 12345 );
00261 
00262     FloatPropertyWPtr float_prop =
00263       pm->createProperty<FloatProperty>( "Size", "",
00264                                          boost::bind( &MyPropertyReceiver::getFloat, &recvr3 ),
00265                                          boost::bind( &MyPropertyReceiver::setFloat, &recvr3, _1 ),
00266                                          options_category, NULL );
00267     setPropertyHelpText(float_prop, "Size of the basket in furlongs.");
00268     FloatPropertyPtr fp = float_prop.lock();
00269     fp->set( 1.398 );
00270 
00271     EditEnumPropertyWPtr ee_prop =
00272       pm->createProperty<EditEnumProperty>( "Callback Enum", "",
00273                                             boost::bind( &MyPropertyReceiver::getEE, &recvr3 ),
00274                                             boost::bind( &MyPropertyReceiver::setEE, &recvr3, _1 ),
00275                                             options_category, NULL );
00276     setPropertyHelpText(ee_prop, "A sample editable enum property.");
00277     EditEnumPropertyPtr eep = ee_prop.lock();
00278     eep->setOptionCallback( boost::bind(&MyPropertyReceiver::optionCallback, &recvr3, _1 ));
00279     eep->set( "Caller pays" );
00280 
00281     Vector3PropertyWPtr vector3_prop =
00282       pm->createProperty<Vector3Property>( "Location", "",
00283                                            boost::bind( &MyPropertyReceiver::getVector3, &recvr3 ),
00284                                            boost::bind( &MyPropertyReceiver::setVector3, &recvr3, _1 ),
00285                                            options_category, NULL );
00286     setPropertyHelpText(vector3_prop, "Location of the basket in furlongs.");
00287     Vector3PropertyPtr vp = vector3_prop.lock();
00288     vp->set( Ogre::Vector3( 1.1, 2.2, 3.3 ));
00289 
00290     QuaternionPropertyWPtr quat_prop =
00291       pm->createProperty<QuaternionProperty>( "Orientation", "",
00292                                               boost::bind( &MyPropertyReceiver::getQuaternion, &recvr3 ),
00293                                               boost::bind( &MyPropertyReceiver::setQuaternion, &recvr3, _1 ),
00294                                               options_category, NULL );
00295     setPropertyHelpText(quat_prop, "Orientation of the basket.");
00296     QuaternionPropertyPtr qp = quat_prop.lock();
00297     qp->set( Ogre::Quaternion( 1.1, 2.2, 3.3, 4.4 ));
00298 
00299   }
00300 
00301   PropertyTreeWithHelp tree_widget;
00302   pm->setPropertyTreeWidget( tree_widget.getTree() );
00303 
00304   tree_widget.show();
00305 
00306   int ret = app.exec();
00307 
00308   delete pm;
00309 
00310   return ret;
00311 }


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:53