00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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
00113
00114 FrameManagerPtr frame_manager = FrameManager::instance();
00115
00116 QApplication app(argc, argv);
00117
00118 RosSpinner spinner;
00119
00120 MyPropertyReceiver recvr( 1 );
00121 MyPropertyReceiver recvr2( 2 );
00122 MyPropertyReceiver recvr3( 3 );
00123
00124 pm = new PropertyManager();
00125 {
00126 CategoryPropertyWPtr options_category = pm->createCategory( ".Global Options", "",
00127 CategoryPropertyWPtr(), NULL );
00128 BoolPropertyWPtr bool_prop =
00129 pm->createProperty<BoolProperty>( "Lumpy", "",
00130 boost::bind( &MyPropertyReceiver::getBool, &recvr ),
00131 boost::bind( &MyPropertyReceiver::setBool, &recvr, _1 ),
00132 options_category, NULL );
00133 setPropertyHelpText(bool_prop, "A sample boolean property.");
00134 BoolPropertyPtr bp = bool_prop.lock();
00135 bp->set( true );
00136
00137 StringPropertyWPtr string_prop =
00138 pm->createProperty<StringProperty>( "Style", "",
00139 boost::bind( &MyPropertyReceiver::getString, &recvr ),
00140 boost::bind( &MyPropertyReceiver::setString, &recvr, _1 ),
00141 options_category, NULL );
00142 setPropertyHelpText(string_prop, "A sample stringean property.");
00143 StringPropertyPtr sp = string_prop.lock();
00144 sp->set( "nubby" );
00145
00146 ColorPropertyWPtr color_prop =
00147 pm->createProperty<ColorProperty>( "Cheese Color", "",
00148 boost::bind( &MyPropertyReceiver::getColor, &recvr ),
00149 boost::bind( &MyPropertyReceiver::setColor, &recvr, _1 ),
00150 options_category, NULL );
00151 setPropertyHelpText(color_prop, "A sample color property.");
00152 ColorPropertyPtr cp = color_prop.lock();
00153 cp->set( Color( .1f, .4f, 1.0f ));
00154
00155 EnumPropertyWPtr enum_prop =
00156 pm->createProperty<EnumProperty>( "Cheese Enum", "",
00157 boost::bind( &MyPropertyReceiver::getEnum, &recvr ),
00158 boost::bind( &MyPropertyReceiver::setEnum, &recvr, _1 ),
00159 options_category, NULL );
00160 setPropertyHelpText(enum_prop, "A sample enum property.");
00161 EnumPropertyPtr ep = enum_prop.lock();
00162 ep->addOption( "cheddar", 6 );
00163 ep->addOption( "swiss", 7 );
00164 ep->addOption( "Humboldt Fog", 99 );
00165 ep->addOption( "chester", -1 );
00166 ep->addOption( "blubber", 0 );
00167 ep->set( 7 );
00168
00169 TFFramePropertyWPtr tf_prop =
00170 pm->createProperty<TFFrameProperty>( "Picture Frame", "",
00171 boost::bind( &MyPropertyReceiver::getTF, &recvr ),
00172 boost::bind( &MyPropertyReceiver::setTF, &recvr, _1 ),
00173 options_category, NULL );
00174 setPropertyHelpText(tf_prop, "A sample tf frame property.");
00175 TFFramePropertyPtr tfp = tf_prop.lock();
00176 tfp->set( "base_link" );
00177
00178 EditEnumPropertyWPtr ee_prop =
00179 pm->createProperty<EditEnumProperty>( "Chub Enum", "",
00180 boost::bind( &MyPropertyReceiver::getEE, &recvr ),
00181 boost::bind( &MyPropertyReceiver::setEE, &recvr, _1 ),
00182 options_category, NULL );
00183 setPropertyHelpText(ee_prop, "A sample editable enum property.");
00184 EditEnumPropertyPtr eep = ee_prop.lock();
00185 eep->addOption( "Tubby" );
00186 eep->addOption( "Portly" );
00187 eep->addOption( "Chunky" );
00188 eep->addOption( "Chunkstyle" );
00189 eep->addOption( "Round" );
00190 eep->set( "Portly" );
00191
00192 IntPropertyWPtr int_prop =
00193 pm->createProperty<IntProperty>( "Planet Number", "",
00194 boost::bind( &MyPropertyReceiver::getInt, &recvr2 ),
00195 boost::bind( &MyPropertyReceiver::setInt, &recvr2, _1 ),
00196 options_category, NULL );
00197 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>.");
00198 IntPropertyPtr ip = int_prop.lock();
00199 ip->set( 3 );
00200 ip->setMax( 9 );
00201 ip->setMin( 1 );
00202
00203 FloatPropertyWPtr float_prop =
00204 pm->createProperty<FloatProperty>( "Alpha", "",
00205 boost::bind( &MyPropertyReceiver::getFloat, &recvr2 ),
00206 boost::bind( &MyPropertyReceiver::setFloat, &recvr2, _1 ),
00207 options_category, NULL );
00208 setPropertyHelpText(float_prop, "Opacity.");
00209 FloatPropertyPtr fp = float_prop.lock();
00210 fp->set( 0.5 );
00211 fp->setMax( 1.0 );
00212 fp->setMin( 0 );
00213 }
00214 {
00215 CategoryPropertyWPtr options_category = pm->createCheckboxCategory( "Pedestrian", "", "",
00216 boost::bind( &MyPropertyReceiver::getBool, &recvr2 ),
00217 boost::bind( &MyPropertyReceiver::setBool, &recvr2, _1 ));
00218 StatusPropertyWPtr stat_prop = pm->createStatus( "Options Status", "prop_prefix", options_category );
00219 {
00220 StatusPropertyPtr sp = stat_prop.lock();
00221 sp->setStatus( status_levels::Error, "Bread", "moldy" );
00222 sp->setStatus( status_levels::Ok, "Orange Juice", "tasty" );
00223 sp->setStatus( status_levels::Warn, "Cheese", "hard and crusty" );
00224 sp->setStatus( status_levels::Warn, "Lemons", "too tangy" );
00225 recvr.setStatusProperty( sp );
00226 }
00227 ROSTopicStringPropertyWPtr topic_prop =
00228 pm->createProperty<ROSTopicStringProperty>( "Topic", "",
00229 boost::bind( &MyPropertyReceiver::getTopic, &recvr3 ),
00230 boost::bind( &MyPropertyReceiver::setTopic, &recvr3, _1 ),
00231 options_category, NULL );
00232 setPropertyHelpText(topic_prop, "What topic to listen to.");
00233 ROSTopicStringPropertyPtr tp = topic_prop.lock();
00234 tp->setMessageType( "std_msgs/String" );
00235 tp->set( "chatter" );
00236
00237 BoolPropertyWPtr bool_prop =
00238 pm->createProperty<BoolProperty>( "Active", "",
00239 boost::bind( &MyPropertyReceiver::getBool, &recvr3 ),
00240 boost::bind( &MyPropertyReceiver::setBool, &recvr3, _1 ),
00241 options_category, NULL );
00242 setPropertyHelpText(bool_prop, "A sample boolean property.");
00243 BoolPropertyPtr bp = bool_prop.lock();
00244 bp->set( true );
00245
00246 StringPropertyWPtr string_prop =
00247 pm->createProperty<StringProperty>( "Cheese type", "",
00248 boost::bind( &MyPropertyReceiver::getString, &recvr3 ),
00249 boost::bind( &MyPropertyReceiver::setString, &recvr3, _1 ),
00250 options_category, NULL );
00251 setPropertyHelpText(string_prop, "A sample stringean property.");
00252 StringPropertyPtr sp = string_prop.lock();
00253 sp->set( "nubby" );
00254
00255 IntPropertyWPtr int_prop =
00256 pm->createProperty<IntProperty>( "NumLemons", "",
00257 boost::bind( &MyPropertyReceiver::getInt, &recvr3 ),
00258 boost::bind( &MyPropertyReceiver::setInt, &recvr3, _1 ),
00259 options_category, NULL );
00260 setPropertyHelpText(int_prop, "Number of lemons in a basket.");
00261 IntPropertyPtr ip = int_prop.lock();
00262 ip->set( 12345 );
00263
00264 FloatPropertyWPtr float_prop =
00265 pm->createProperty<FloatProperty>( "Size", "",
00266 boost::bind( &MyPropertyReceiver::getFloat, &recvr3 ),
00267 boost::bind( &MyPropertyReceiver::setFloat, &recvr3, _1 ),
00268 options_category, NULL );
00269 setPropertyHelpText(float_prop, "Size of the basket in furlongs.");
00270 FloatPropertyPtr fp = float_prop.lock();
00271 fp->set( 1.398 );
00272
00273 EditEnumPropertyWPtr ee_prop =
00274 pm->createProperty<EditEnumProperty>( "Callback Enum", "",
00275 boost::bind( &MyPropertyReceiver::getEE, &recvr3 ),
00276 boost::bind( &MyPropertyReceiver::setEE, &recvr3, _1 ),
00277 options_category, NULL );
00278 setPropertyHelpText(ee_prop, "A sample editable enum property.");
00279 EditEnumPropertyPtr eep = ee_prop.lock();
00280 eep->setOptionCallback( boost::bind(&MyPropertyReceiver::optionCallback, &recvr3, _1 ));
00281 eep->set( "Caller pays" );
00282
00283 Vector3PropertyWPtr vector3_prop =
00284 pm->createProperty<Vector3Property>( "Location", "",
00285 boost::bind( &MyPropertyReceiver::getVector3, &recvr3 ),
00286 boost::bind( &MyPropertyReceiver::setVector3, &recvr3, _1 ),
00287 options_category, NULL );
00288 setPropertyHelpText(vector3_prop, "Location of the basket in furlongs.");
00289 Vector3PropertyPtr vp = vector3_prop.lock();
00290 vp->set( Ogre::Vector3( 1.1, 2.2, 3.3 ));
00291
00292 QuaternionPropertyWPtr quat_prop =
00293 pm->createProperty<QuaternionProperty>( "Orientation", "",
00294 boost::bind( &MyPropertyReceiver::getQuaternion, &recvr3 ),
00295 boost::bind( &MyPropertyReceiver::setQuaternion, &recvr3, _1 ),
00296 options_category, NULL );
00297 setPropertyHelpText(quat_prop, "Orientation of the basket.");
00298 QuaternionPropertyPtr qp = quat_prop.lock();
00299 qp->set( Ogre::Quaternion( 1.1, 2.2, 3.3, 4.4 ));
00300
00301 }
00302
00303 PropertyTreeWithHelp tree_widget;
00304 pm->setPropertyTreeWidget( tree_widget.getTree() );
00305
00306 tree_widget.show();
00307
00308 int ret = app.exec();
00309
00310 delete pm;
00311
00312 return ret;
00313 }