$search
00001 /* 00002 * Copyright (c) 2008, 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 #ifndef RVIZ_PROPERTY_H 00031 #define RVIZ_PROPERTY_H 00032 00033 #include "rviz/helpers/color.h" 00034 #include "forwards.h" 00035 #include "rviz/status_level.h" 00036 00037 #include <boost/function.hpp> 00038 #include <boost/signal.hpp> 00039 #include <boost/enable_shared_from_this.hpp> 00040 #include <boost/thread/mutex.hpp> 00041 00042 #include <ros/console.h> 00043 #include <ros/assert.h> 00044 00045 #include <wx/string.h> 00046 #include <wx/colour.h> 00047 00048 #include <OGRE/OgreVector3.h> 00049 #include <OGRE/OgreQuaternion.h> 00050 00051 #include <string> 00052 #include <vector> 00053 00054 class wxConfigBase; 00055 class wxPropertyGrid; 00056 class wxPGProperty; 00057 class wxColour; 00058 class wxPGChoices; 00059 00060 namespace rviz 00061 { 00062 00063 class CategoryProperty; 00064 class VisualizationManager; 00065 00066 void setPropertyHelpText(wxPGProperty* property, const std::string& text); 00067 void setPropertyToColors(wxPGProperty* property, const wxColour& fg_color, const wxColour& bg_color, uint32_t column = 0); 00068 void setPropertyToError(wxPGProperty* property, uint32_t column = 0); 00069 void setPropertyToWarn(wxPGProperty* property, uint32_t column = 0); 00070 void setPropertyToOK(wxPGProperty* property, uint32_t column = 0); 00071 void setPropertyToDisabled(wxPGProperty* property, uint32_t column = 0); 00072 void setPropertyName(wxPGProperty* property, const wxString& name); 00073 00077 class PropertyBase : public boost::enable_shared_from_this<PropertyBase> 00078 { 00079 public: 00080 typedef boost::signal< void (const PropertyBasePtr&) > ChangedSignal; 00081 00082 PropertyBase(); 00083 virtual ~PropertyBase(); 00084 virtual void writeToGrid() = 0; 00085 virtual void readFromGrid() = 0; 00086 virtual void saveToConfig( wxConfigBase* config ) = 0; 00087 virtual void loadFromConfig( wxConfigBase* config ) = 0; 00088 00089 virtual std::string getName() = 0; 00090 virtual std::string getPrefix() = 0; 00091 virtual void setPrefix(const std::string& prefix) = 0; 00092 virtual bool getSave() = 0; 00093 00094 virtual void* getUserData() = 0; 00095 00096 virtual wxPGProperty* getPGProperty() = 0; 00097 00098 virtual CategoryPropertyWPtr getParent() = 0; 00099 00100 virtual void addLegacyName(const std::string& name) = 0; 00101 00102 virtual void setPGClientData(); 00103 virtual void setPropertyGrid(wxPropertyGrid* grid); 00104 00105 virtual void setUserData(void* user_data) = 0; 00106 00107 virtual void reset() 00108 { 00109 grid_ = 0; 00110 property_ = 0; 00111 } 00112 00113 virtual void show(); 00114 virtual void hide(); 00115 00116 virtual bool isSelected(); 00117 00122 void addChangedListener( const ChangedSignal::slot_type& slot ) 00123 { 00124 changed_.connect( slot ); 00125 } 00126 00130 void changed() 00131 { 00132 changed_( shared_from_this() ); 00133 } 00134 00135 protected: 00136 wxPropertyGrid* grid_; 00137 wxPGProperty* property_; 00138 00139 ChangedSignal changed_; 00140 }; 00141 00142 class StatusProperty : public PropertyBase 00143 { 00144 public: 00145 StatusProperty(const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, void* user_data); 00146 ~StatusProperty(); 00147 00148 virtual void writeToGrid(); 00149 virtual void readFromGrid() {} 00150 virtual void saveToConfig(wxConfigBase* config) {} 00151 virtual void loadFromConfig(wxConfigBase* config) {} 00152 00153 virtual std::string getName() { return (const char*)name_.char_str(); } 00154 virtual std::string getPrefix() { return (const char*)name_.char_str(); } 00155 virtual void setPrefix(const std::string& prefix); 00156 virtual bool getSave() { return false; } 00157 virtual void* getUserData() { return user_data_; } 00158 00159 virtual CategoryPropertyWPtr getParent() { return parent_; } 00160 00161 virtual wxPGProperty* getPGProperty() { return 0; } 00162 virtual void addLegacyName(const std::string& name) {} 00163 00164 virtual void setPGClientData(); 00165 00166 virtual void setUserData(void* user_data) { user_data_ = user_data; } 00167 00168 void setStatus(StatusLevel status, const std::string& name, const std::string& text); 00169 void deleteStatus(const std::string& name); 00170 void clear(); 00171 00172 void disable(); 00173 void enable(); 00174 00175 StatusLevel getTopLevelStatus(); 00176 00177 private: 00178 void updateTopLevelStatus(); 00179 00180 wxString name_; 00181 wxString prefix_; 00182 CategoryPropertyWPtr parent_; 00183 void* user_data_; 00184 00185 wxPGProperty* top_property_; 00186 00187 struct Status 00188 { 00189 Status() 00190 : level(status_levels::Ok) 00191 , property(0) 00192 , kill(false) 00193 {} 00194 00195 StatusLevel level; 00196 wxString name; 00197 wxString text; 00198 wxPGProperty* property; 00199 bool kill; 00200 }; 00201 typedef std::map<std::string, Status> M_StringToStatus; 00202 boost::mutex status_mutex_; 00203 M_StringToStatus statuses_; 00204 00205 bool enabled_; 00206 bool prefix_changed_; 00207 00208 StatusLevel top_status_; 00209 }; 00210 00220 template<typename T> 00221 class Property : public PropertyBase 00222 { 00223 public: 00224 typedef boost::function<T (void)> Getter; 00225 typedef boost::function<void (const T&)> Setter; 00226 00227 public: 00239 Property( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00240 : name_( wxString::FromAscii( name.c_str() ) ) 00241 , prefix_( wxString::FromAscii( prefix.c_str() ) ) 00242 , parent_( parent ) 00243 , save_( true ) 00244 , user_data_( 0 ) 00245 , getter_( getter ) 00246 , setter_( setter ) 00247 { 00248 if ( setter_ == 0 ) 00249 { 00250 save_ = false; 00251 } 00252 } 00253 00257 virtual ~Property() 00258 { 00259 } 00260 00265 T get() { return getter_(); } 00270 void set( const T& val ) 00271 { 00272 setter_( val ); 00273 00274 changed(); 00275 } 00276 00277 bool hasGetter() { return getter_ != 0; } 00278 bool hasSetter() { return setter_ != 0; } 00279 00284 void setSave( bool save ) { save_ = save; } 00288 bool getSave() { return save_; } 00289 00294 virtual std::string getName() { return (const char*)name_.mb_str(); } 00299 virtual std::string getPrefix() { return (const char*)prefix_.mb_str(); } 00300 00305 virtual wxPGProperty* getPGProperty() 00306 { 00307 return property_; 00308 } 00309 00313 void* getUserData() { return user_data_; } 00318 void setUserData(void* user_data) 00319 { 00320 user_data_ = user_data; 00321 } 00322 00323 virtual CategoryPropertyWPtr getParent() { return parent_; } 00324 00325 virtual void addLegacyName(const std::string& name) 00326 { 00327 legacy_names_.push_back(wxString::FromAscii(name.c_str())); 00328 } 00329 00330 virtual void setToError() 00331 { 00332 setPropertyToError(property_); 00333 } 00334 00335 virtual void setToWarn() 00336 { 00337 setPropertyToWarn(property_); 00338 } 00339 00340 virtual void setToOK() 00341 { 00342 setPropertyToOK(property_); 00343 } 00344 00345 virtual void setToDisabled() 00346 { 00347 setPropertyToDisabled(property_); 00348 } 00349 00350 virtual void setHelpText(const std::string& text) 00351 { 00352 help_text_ = text; 00353 changed(); 00354 } 00355 00356 virtual void setPrefix(const std::string& prefix) 00357 { 00358 prefix_ = wxString::FromAscii(prefix.c_str()); 00359 setPropertyName(property_, prefix_ + name_); 00360 } 00361 00362 protected: 00363 wxString name_; 00364 wxString prefix_; 00365 CategoryPropertyWPtr parent_; 00366 00367 bool save_; 00368 00369 void* user_data_; 00370 00371 typedef std::vector<wxString> V_wxString; 00372 V_wxString legacy_names_; 00373 00374 std::string help_text_; 00375 00376 private: 00377 Getter getter_; 00378 Setter setter_; 00379 }; 00380 00381 class BoolProperty : public Property<bool> 00382 { 00383 public: 00384 BoolProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00385 : Property<bool>( name, prefix, parent, getter, setter ) 00386 { 00387 } 00388 00389 virtual void writeToGrid(); 00390 virtual void readFromGrid(); 00391 virtual void saveToConfig( wxConfigBase* config ); 00392 virtual void loadFromConfig( wxConfigBase* config ); 00393 }; 00394 00395 class IntProperty : public Property<int> 00396 { 00397 public: 00398 IntProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00399 : Property<int>( name, prefix, parent, getter, setter ) 00400 { 00401 } 00402 00403 void setMin( int min ); 00404 void setMax( int max ); 00405 00406 virtual void writeToGrid(); 00407 virtual void readFromGrid(); 00408 virtual void saveToConfig( wxConfigBase* config ); 00409 virtual void loadFromConfig( wxConfigBase* config ); 00410 }; 00411 00412 class FloatProperty : public Property<float> 00413 { 00414 public: 00415 FloatProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00416 : Property<float>( name, prefix, parent, getter, setter ) 00417 { 00418 } 00419 00420 void setMin( float min ); 00421 void setMax( float max ); 00422 00423 virtual void writeToGrid(); 00424 virtual void readFromGrid(); 00425 virtual void saveToConfig( wxConfigBase* config ); 00426 virtual void loadFromConfig( wxConfigBase* config ); 00427 }; 00428 00429 class DoubleProperty : public Property<double> 00430 { 00431 public: 00432 DoubleProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00433 : Property<double>( name, prefix, parent, getter, setter ) 00434 { 00435 } 00436 00437 void setMin( double min ); 00438 void setMax( double max ); 00439 00440 virtual void writeToGrid(); 00441 virtual void readFromGrid(); 00442 virtual void saveToConfig( wxConfigBase* config ); 00443 virtual void loadFromConfig( wxConfigBase* config ); 00444 }; 00445 00446 class StringProperty : public Property<std::string> 00447 { 00448 public: 00449 StringProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00450 : Property<std::string>( name, prefix, parent, getter, setter ) 00451 { 00452 } 00453 00454 virtual void writeToGrid(); 00455 virtual void readFromGrid(); 00456 virtual void saveToConfig( wxConfigBase* config ); 00457 virtual void loadFromConfig( wxConfigBase* config ); 00458 }; 00459 00460 class ROSTopicProperty; 00461 class ROSTopicStringProperty : public StringProperty 00462 { 00463 public: 00464 ROSTopicStringProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00465 : StringProperty( name, prefix, parent, getter, setter ) 00466 { 00467 } 00468 00469 void setMessageType(const std::string& message_type); 00470 00471 virtual void writeToGrid(); 00472 00473 private: 00474 std::string message_type_; 00475 ROSTopicProperty* ros_topic_property_; 00476 }; 00477 00478 class ColorProperty : public Property<Color> 00479 { 00480 public: 00481 ColorProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00482 : Property<Color>( name, prefix, parent, getter, setter ) 00483 { 00484 } 00485 00486 virtual void writeToGrid(); 00487 virtual void readFromGrid(); 00488 virtual void saveToConfig( wxConfigBase* config ); 00489 virtual void loadFromConfig( wxConfigBase* config ); 00490 }; 00491 00492 class EnumProperty : public Property<int> 00493 { 00494 public: 00495 EnumProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ); 00496 00497 void addOption( const std::string& name, int value ); 00498 void clear (); 00499 00500 virtual void writeToGrid(); 00501 virtual void readFromGrid(); 00502 virtual void saveToConfig( wxConfigBase* config ); 00503 virtual void loadFromConfig( wxConfigBase* config ); 00504 00505 private: 00506 boost::shared_ptr<wxPGChoices> choices_; 00507 00508 boost::mutex mutex_; 00509 }; 00510 00511 class EditEnumProperty : public Property<std::string> 00512 { 00513 public: 00514 EditEnumProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ); 00515 00516 void addOption( const std::string& name ); 00517 void clear (); 00518 00519 void setOptionCallback(const EditEnumOptionCallback& cb); 00520 00521 virtual void writeToGrid(); 00522 virtual void readFromGrid(); 00523 virtual void saveToConfig( wxConfigBase* config ); 00524 virtual void loadFromConfig( wxConfigBase* config ); 00525 00526 private: 00527 boost::shared_ptr<wxPGChoices> choices_; 00528 EditEnumOptionCallback option_cb_; 00529 EditEnumPGProperty* ee_property_; 00530 00531 boost::mutex mutex_; 00532 }; 00533 00534 class TFFramePGProperty; 00535 class TFFrameProperty : public EditEnumProperty 00536 { 00537 public: 00538 TFFrameProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00539 : EditEnumProperty( name, prefix, parent, getter, setter ) 00540 { 00541 } 00542 00543 virtual void writeToGrid(); 00544 00545 private: 00546 TFFramePGProperty* tf_frame_property_; 00547 }; 00548 00549 00550 class CategoryProperty : public Property<bool> 00551 { 00552 public: 00553 CategoryProperty( const std::string& label, const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter, bool checkbox ) 00554 : Property<bool>( name, prefix, parent, getter, setter ) 00555 , label_(wxString::FromAscii(label.c_str())) 00556 , checkbox_(checkbox) 00557 { 00558 } 00559 00560 void setLabel( const std::string& label ); 00561 void expand(); 00562 void collapse(); 00563 00564 virtual void writeToGrid(); 00565 virtual void readFromGrid(); 00566 virtual void saveToConfig( wxConfigBase* config ); 00567 virtual void loadFromConfig( wxConfigBase* config ); 00568 00569 virtual void setToError(); 00570 virtual void setToWarn(); 00571 virtual void setToOK(); 00572 virtual void setToDisabled(); 00573 00574 private: 00575 wxString label_; 00576 bool checkbox_; 00577 }; 00578 00579 class Vector3Property : public Property<Ogre::Vector3> 00580 { 00581 public: 00582 Vector3Property( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00583 : Property<Ogre::Vector3>( name, prefix, parent, getter, setter ) 00584 , composed_parent_( NULL ) 00585 , x_( NULL ) 00586 , y_( NULL ) 00587 , z_( NULL ) 00588 { 00589 } 00590 00591 virtual ~Vector3Property(); 00592 00593 virtual void writeToGrid(); 00594 virtual void readFromGrid(); 00595 virtual void saveToConfig( wxConfigBase* config ); 00596 virtual void loadFromConfig( wxConfigBase* config ); 00597 virtual void setPGClientData(); 00598 virtual void reset(); 00599 virtual void show(); 00600 virtual void hide(); 00601 virtual void setPrefix(const std::string& prefix); 00602 00603 virtual void setToError() 00604 { 00605 setPropertyToError(composed_parent_); 00606 setPropertyToError(x_); 00607 setPropertyToError(y_); 00608 setPropertyToError(z_); 00609 } 00610 00611 virtual void setToWarn() 00612 { 00613 setPropertyToWarn(composed_parent_); 00614 setPropertyToWarn(x_); 00615 setPropertyToWarn(y_); 00616 setPropertyToWarn(z_); 00617 } 00618 00619 virtual void setToOK() 00620 { 00621 setPropertyToOK(composed_parent_); 00622 setPropertyToOK(x_); 00623 setPropertyToOK(y_); 00624 setPropertyToOK(z_); 00625 } 00626 00627 virtual void setToDisabled() 00628 { 00629 setPropertyToDisabled(composed_parent_); 00630 setPropertyToDisabled(x_); 00631 setPropertyToDisabled(y_); 00632 setPropertyToDisabled(z_); 00633 } 00634 00635 protected: 00636 wxPGProperty* composed_parent_; 00637 wxPGProperty* x_; 00638 wxPGProperty* y_; 00639 wxPGProperty* z_; 00640 }; 00641 00642 class QuaternionProperty : public Property<Ogre::Quaternion> 00643 { 00644 public: 00645 QuaternionProperty( const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, const Getter& getter, const Setter& setter ) 00646 : Property<Ogre::Quaternion>( name, prefix, parent, getter, setter ) 00647 , composed_parent_( NULL ) 00648 , x_( NULL ) 00649 , y_( NULL ) 00650 , z_( NULL ) 00651 , w_( NULL ) 00652 { 00653 } 00654 00655 virtual ~QuaternionProperty(); 00656 00657 virtual void writeToGrid(); 00658 virtual void readFromGrid(); 00659 virtual void saveToConfig( wxConfigBase* config ); 00660 virtual void loadFromConfig( wxConfigBase* config ); 00661 virtual void setPGClientData(); 00662 virtual void reset(); 00663 virtual void show(); 00664 virtual void hide(); 00665 virtual void setPrefix(const std::string& prefix); 00666 00667 virtual void setToError() 00668 { 00669 setPropertyToError(composed_parent_); 00670 setPropertyToError(x_); 00671 setPropertyToError(y_); 00672 setPropertyToError(z_); 00673 setPropertyToError(w_); 00674 } 00675 00676 virtual void setToWarn() 00677 { 00678 setPropertyToWarn(composed_parent_); 00679 setPropertyToWarn(x_); 00680 setPropertyToWarn(y_); 00681 setPropertyToWarn(z_); 00682 setPropertyToWarn(w_); 00683 } 00684 00685 virtual void setToOK() 00686 { 00687 setPropertyToOK(composed_parent_); 00688 setPropertyToOK(x_); 00689 setPropertyToOK(y_); 00690 setPropertyToOK(z_); 00691 setPropertyToOK(w_); 00692 } 00693 00694 virtual void setToDisabled() 00695 { 00696 setPropertyToDisabled(composed_parent_); 00697 setPropertyToDisabled(x_); 00698 setPropertyToDisabled(y_); 00699 setPropertyToDisabled(z_); 00700 setPropertyToDisabled(w_); 00701 } 00702 00703 protected: 00704 wxPGProperty* composed_parent_; 00705 wxPGProperty* x_; 00706 wxPGProperty* y_; 00707 wxPGProperty* z_; 00708 wxPGProperty* w_; 00709 }; 00710 00711 00712 } // namespace rviz 00713 00714 #endif