[rviz] 01/01: Imported Upstream version 1.11.8

Jochen Sprickerhof jspricke-guest at moszumanska.debian.org
Thu Aug 6 06:15:44 UTC 2015


This is an automated email from the git hooks/post-receive script.

jspricke-guest pushed a commit to annotated tag upstream/1.11.8
in repository rviz.

commit 29a7da558d78072c48a74014d2a88ec5edddc8dd
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Thu Aug 6 07:47:37 2015 +0200

    Imported Upstream version 1.11.8
---
 .gitignore                                         |   1 +
 .travis.yml                                        |   1 +
 CHANGELOG.rst                                      |  24 +++
 CMakeLists.txt                                     |  10 +-
 package.xml                                        |   2 +-
 plugin_description.xml                             |   5 +
 rviz.sublime-project                               |  28 +++
 src/CMakeLists.txt                                 |   4 +-
 src/python_bindings/shiboken/CMakeLists.txt        |  14 +-
 src/rviz/config.cpp                                |  11 +
 src/rviz/config.h                                  |   4 +-
 src/rviz/default_plugin/CMakeLists.txt             |   2 +
 src/rviz/default_plugin/marker_display.cpp         |  13 +-
 .../markers/mesh_resource_marker.cpp               |  76 +++----
 .../default_plugin/markers/mesh_resource_marker.h  |   3 +-
 src/rviz/default_plugin/point_cloud_common.cpp     |  24 ++-
 .../default_plugin/point_cloud_transformers.cpp    |  32 ++-
 src/rviz/default_plugin/tf_display.cpp             |   4 +-
 .../third_person_follower_view_controller.cpp      | 239 +++++++++++++++++++++
 .../third_person_follower_view_controller.h}       |  68 +++---
 src/rviz/default_plugin/wrench_display.cpp         |  29 ++-
 src/rviz/default_plugin/wrench_display.h           |   2 +-
 src/rviz/default_plugin/wrench_visual.cpp          |  22 +-
 src/rviz/default_plugin/wrench_visual.h            |   5 +-
 src/rviz/display.cpp                               |   2 +-
 .../frame_position_tracking_view_controller.cpp    |  19 +-
 src/rviz/frame_position_tracking_view_controller.h |   4 +-
 src/rviz/mesh_loader.cpp                           |   2 +-
 src/rviz/ogre_helpers/stl_loader.cpp               |  81 ++++++-
 src/rviz/ogre_helpers/stl_loader.h                 |   6 +-
 src/rviz/robot/robot.cpp                           |  37 ++++
 src/rviz/visualization_frame.cpp                   |   6 +-
 src/rviz/visualization_frame.h                     |   1 +
 src/rviz/visualizer_app.cpp                        |  14 +-
 src/test/CMakeLists.txt                            | 237 ++++++++++----------
 src/test/config_test.cpp                           | 220 ++-----------------
 src/test/display_test.cpp                          |  79 +++----
 src/test/display_test.test                         |   3 +
 src/test/fun_display.cpp                           | 137 ------------
 src/test/image_test.cpp                            |   2 +-
 src/test/meshes/ascii.stl                          |  19 ++
 src/test/meshes/invalid.stl                        | Bin 0 -> 194 bytes
 src/test/meshes/invalid_short.stl                  | Bin 0 -> 70 bytes
 src/test/meshes/valid.stl                          | Bin 0 -> 184 bytes
 src/test/mock_context.h                            |  10 +-
 src/test/new_display_dialog_test.cpp               |  29 ++-
 src/test/other-help.html                           |  12 --
 src/test/playground.cpp                            | 206 ------------------
 src/test/playground.h                              |  54 -----
 src/test/render_panel_test.cpp                     |   3 +-
 src/test/render_points_test.cpp                    |   6 +-
 src/test/render_points_test.h                      |   2 +
 src/test/ros_spinner.h                             |   4 +-
 src/test/rviz_logo_marker.cpp                      |   6 +-
 src/test/stl_loader_test.cpp                       |  33 +++
 src/test/topic_dialog_test.cpp                     |  58 -----
 src/test/topic_info_variant_test.cpp               |  70 ------
 src/test/vis_panel_example.cpp                     |  63 ------
 58 files changed, 932 insertions(+), 1116 deletions(-)

diff --git a/.gitignore b/.gitignore
index 7420793..db54a93 100644
--- a/.gitignore
+++ b/.gitignore
@@ -3,3 +3,4 @@
 bin
 build
 lib
+*.sublime-workspace
diff --git a/.travis.yml b/.travis.yml
index 4349180..8c45388 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -21,6 +21,7 @@ script:
   - cd build
   - cmake .. -DCMAKE_INSTALL_PREFIX=./install
   - make -j1
+  - make -j1 tests
   - make -j1 run_tests
   - catkin_test_results .
   - make -j1 install
diff --git a/CHANGELOG.rst b/CHANGELOG.rst
index e646369..baab814 100644
--- a/CHANGELOG.rst
+++ b/CHANGELOG.rst
@@ -2,6 +2,30 @@
 Changelog for package rviz
 ^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+1.11.8 (2015-08-05)
+-------------------
+* Force and Torque can now be scaled separately in the Wrench display: `#862 <https://github.com/ros-visualization/rviz/issues/862>`_
+* Fixed a bug in the Wrench display: `#883 <https://github.com/ros-visualization/rviz/issues/883>`_
+* Improved error checking when loading ascii stl files.
+* Suppressing some new CMake warnings by setting cmake policies.
+* Re-enable most all of the tests.
+* Added option to start rviz with the ROS logger level set to Debug
+* Fixed setting of status bar from python by checking if the original status bar is being used or not.
+* Added a third person follower view controller.
+* Fix decaying of tf2 static transforms in the TF display.
+* Correctly display color and alpha in pointclouds.
+* Restored functionality to force opacity and color for meshes that have null rgba values.
+* Use the ``find_package``'ed python version detected by catkin.
+  Otherwise it might happen that catkin (and the rest of the workspace)
+  uses 2.x and rviz detects & tries to use 3.x. This can produce some nasty
+  collisions.
+  See rospack, roslz4, qt_gui_cpp and others for similar invokation.
+* Fix processing empty of pointclouds.
+  Otherwise, given a stream of clouds with some of them empty, the last non-empty message will still be displayed until a the next non-empty cloud comes in.
+* Check if position and orientation of links of robots contain NaNs when updating pose of robot links.
+* Fixed DELETEALL marker action, by not iterating on the marker list.
+* Contributors: Carlos Agüero, Gustavo N Goretkin, Jonathan Bohren, Kei Okada, Michael Ferguson, Ryohei Ueda, Thomas Moinel, William Woodall, loganE, louise, otim, v4hn, 寺田 耕志
+
 1.11.7 (2015-03-02)
 -------------------
 * Fixed a bug where the timestamp was not set for the /initialpose message published by the 2D Pose Estimate tool.
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6fb40bb..189ebee 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,6 +1,13 @@
 cmake_minimum_required(VERSION 2.8.3)
 project(rviz)
 
+if (POLICY CMP0042)
+  cmake_policy(SET CMP0042 NEW)
+endif()
+if (POLICY CMP0054)
+  cmake_policy(SET CMP0054 NEW)
+endif()
+
 find_package(Boost REQUIRED
   COMPONENTS
   filesystem
@@ -84,8 +91,6 @@ endif()
 
 find_package(OpenGL REQUIRED)
 
-find_package(PythonLibs REQUIRED)
-
 find_package(Qt4 REQUIRED COMPONENTS QtCore QtGui QtOpenGL)
 
 find_package(catkin REQUIRED
@@ -120,6 +125,7 @@ if(${tf_VERSION} VERSION_LESS "1.11.3")
   add_definitions("-DRVIZ_USE_BOOST_SIGNAL_1")
 endif()
 
+find_package(PythonLibs "${PYTHON_VERSION_MAJOR}.${PYTHON_VERSION_MINOR}" REQUIRED)
 
 find_package(Eigen REQUIRED)
 
diff --git a/package.xml b/package.xml
index fdd6727..12c3b5b 100644
--- a/package.xml
+++ b/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rviz</name>
-  <version>1.11.7</version>
+  <version>1.11.8</version>
   <description>
      3D visualization tool for ROS.
   </description>
diff --git a/plugin_description.xml b/plugin_description.xml
index 4e7da7b..129fbf3 100644
--- a/plugin_description.xml
+++ b/plugin_description.xml
@@ -253,6 +253,11 @@
       Makes it easy to move around a given point on the XY plane, looking at it from any angle.
     </description>
   </class>
+  <class name="rviz/ThirdPersonFollower" type="rviz::ThirdPersonFollowerViewController" base_class_type="rviz::ViewController">
+    <description>
+      Follow a target frame and turn the viewing direction with the yaw of the target frame.
+    </description>
+  </class>
   <class name="rviz/FPS" type="rviz::FPSViewController" base_class_type="rviz::ViewController">
     <description>
       Control the camera like in a First Person Shooter game: drag left to look left, etc.
diff --git a/rviz.sublime-project b/rviz.sublime-project
new file mode 100644
index 0000000..37379a3
--- /dev/null
+++ b/rviz.sublime-project
@@ -0,0 +1,28 @@
+{
+	"folders":
+	[
+		{
+			"path": "."
+		}
+	],
+	"settings":
+	{
+		"sublimeclang_options":
+		[
+			"-framework QtCore",
+			"-framework QtGui",
+			"-I/usr/local/Cellar/qt/4.8.6/lib/QtCore.framework/Versions/4/Headers",
+			"-I/usr/local/Cellar/qt/4.8.6/lib/QtGui.framework/Versions/4/Headers",
+			"-I/usr/local/Cellar/ogre-1.9/1.9.0/include",
+			"-I/usr/local/Cellar/ogre-1.9/1.9.0/include/OGRE",
+			"-I/Users/william/indigo/install/include",
+			"-I${folder:${project_path:rviz.sublime-project}}/src",
+			"-I/Library/Developer/CommandLineTools/usr/bin/../include/c++/v1",
+			"-I/usr/local/include",
+			"-I/Library/Developer/CommandLineTools/usr/bin/../lib/clang/6.1.0/include",
+			"-I/Library/Developer/CommandLineTools/usr/include",
+			"-I/usr/include",
+			"-Wno-deprecated-register"
+		]
+	}
+}
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 0ffeb4c..bf61488 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -1,4 +1,6 @@
 add_subdirectory(rviz)
 add_subdirectory(image_view)
-add_subdirectory(test)
+if (CATKIN_ENABLE_TESTING)
+  add_subdirectory(test)
+endif()
 add_subdirectory(python_bindings)
diff --git a/src/python_bindings/shiboken/CMakeLists.txt b/src/python_bindings/shiboken/CMakeLists.txt
index 60a03ed..c8a5b8d 100644
--- a/src/python_bindings/shiboken/CMakeLists.txt
+++ b/src/python_bindings/shiboken/CMakeLists.txt
@@ -9,10 +9,18 @@ find_package(python_qt_binding REQUIRED)
 include(${python_qt_binding_EXTRAS_DIR}/shiboken_helper.cmake)
 
 if(shiboken_helper_FOUND)
+  set(_configure_shiboken TRUE)
   if(Shiboken_VERSION VERSION_GREATER "1.1.1")
-    # shiboken 1.1.2 and higher will segfault until https://bugreports.qt-project.org/browse/PYSIDE-218 is fixed
-    message(WARNING "Shiboken version ${Shiboken_VERSION} would segfault when trying to process rviz (see https://bugreports.qt-project.org/browse/PYSIDE-218). Therefore shiboken bindings are being skipped.")
-  else()
+    if(APPLE AND Shiboken_VERSION VERSION_GREATER "1.2.1")
+      # This appears to no longer be a problem at least with Shiboken 1.2.2 on OS X and Boost 1.57.
+      set(_configure_shiboken TRUE)
+    else()
+      # shiboken 1.1.2 and higher will segfault until https://bugreports.qt-project.org/browse/PYSIDE-218 is fixed
+      set(_configure_shiboken FALSE)
+      message(WARNING "Shiboken version ${Shiboken_VERSION} would segfault when trying to process rviz (see https://bugreports.qt-project.org/browse/PYSIDE-218). Therefore shiboken bindings are being skipped.")
+    endif()
+  endif()
+  if(_configure_shiboken)
     list(APPEND rviz_BINDINGS "shiboken")
     set(rviz_BINDINGS "${rviz_BINDINGS}" PARENT_SCOPE)
 
diff --git a/src/rviz/config.cpp b/src/rviz/config.cpp
index 009b851..be564f7 100644
--- a/src/rviz/config.cpp
+++ b/src/rviz/config.cpp
@@ -27,6 +27,8 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
+#include <QLocale>
+
 #include "rviz/config.h"
 
 namespace rviz
@@ -252,6 +254,15 @@ bool Config::mapGetFloat( const QString& key, float *value_out ) const
       *value_out = f;
       return true;
     }
+    QString as_string = v.toString();
+    // Try as European, e.g. 1.234,56 rather than 1,234.56
+    QLocale german(QLocale::German);
+    f = german.toFloat(as_string, &ok);
+    if ( ok )
+    {
+      *value_out = f;
+      return true;
+    }
   }
   return false;
 }
diff --git a/src/rviz/config.h b/src/rviz/config.h
index c4f62fd..bbaeba8 100644
--- a/src/rviz/config.h
+++ b/src/rviz/config.h
@@ -78,7 +78,7 @@ namespace rviz
  *    {
  *      resize( width, height );
  *    }
- *    
+ *
  *    Config file_list_config = config.mapGetChild( "Files" );
  *    filenames_.clear();
  *    int num_files = file_list_config.listLength();
@@ -287,7 +287,7 @@ public:
      *
      * This is how you tell if your loop over entries is at the end. */
     bool isValid();
-  
+
     /** @brief Resets the iterator to the start of the map. */
     void start();
 
diff --git a/src/rviz/default_plugin/CMakeLists.txt b/src/rviz/default_plugin/CMakeLists.txt
index 8e8a3ad..797d96f 100644
--- a/src/rviz/default_plugin/CMakeLists.txt
+++ b/src/rviz/default_plugin/CMakeLists.txt
@@ -39,6 +39,7 @@ qt4_wrap_cpp(MOC_FILES
   tools/point_tool.h
   view_controllers/orbit_view_controller.h
   view_controllers/xy_orbit_view_controller.h
+  view_controllers/third_person_follower_view_controller.h
   view_controllers/fixed_orientation_ortho_view_controller.h
   view_controllers/fps_view_controller.h
   wrench_display.h
@@ -101,6 +102,7 @@ set(SOURCE_FILES
   tools/interaction_tool.cpp
   view_controllers/orbit_view_controller.cpp
   view_controllers/xy_orbit_view_controller.cpp
+  view_controllers/third_person_follower_view_controller.cpp
   view_controllers/fixed_orientation_ortho_view_controller.cpp
   view_controllers/fps_view_controller.cpp
   wrench_display.cpp
diff --git a/src/rviz/default_plugin/marker_display.cpp b/src/rviz/default_plugin/marker_display.cpp
index f71c417..28f580e 100644
--- a/src/rviz/default_plugin/marker_display.cpp
+++ b/src/rviz/default_plugin/marker_display.cpp
@@ -206,10 +206,16 @@ void MarkerDisplay::deleteMarkersInNamespace( const std::string& ns )
 
 void MarkerDisplay::deleteAllMarkers()
 {
+  std::vector<MarkerID> to_delete;
   M_IDToMarker::iterator marker_it = markers_.begin();
   for (; marker_it != markers_.end(); ++marker_it)
   {
-    deleteMarker( marker_it->first );
+    to_delete.push_back(marker_it->first);
+  }
+
+  for (std::vector<MarkerID>::iterator it = to_delete.begin(); it != to_delete.end(); ++it)
+  {
+    deleteMarker( *it );
   }
 }
 
@@ -250,6 +256,11 @@ void MarkerDisplay::incomingMarker( const visualization_msgs::Marker::ConstPtr&
 void MarkerDisplay::failedMarker(const ros::MessageEvent<visualization_msgs::Marker>& marker_evt, tf::FilterFailureReason reason)
 {
   visualization_msgs::Marker::ConstPtr marker = marker_evt.getConstMessage();
+  if (marker->action == visualization_msgs::Marker::DELETE ||
+      marker->action == 3)  // TODO: visualization_msgs::Marker::DELETEALL when message changes in a future version of ROS
+  {
+    return this->processMessage(marker);
+  }
   std::string authority = marker_evt.getPublisherName();
   std::string error = context_->getFrameManager()->discoverFailureReason(marker->header.frame_id, marker->header.stamp, authority, reason);
   setMarkerStatus(MarkerID(marker->ns, marker->id), StatusProperty::Error, error);
diff --git a/src/rviz/default_plugin/markers/mesh_resource_marker.cpp b/src/rviz/default_plugin/markers/mesh_resource_marker.cpp
index 1759f09..9ea7470 100644
--- a/src/rviz/default_plugin/markers/mesh_resource_marker.cpp
+++ b/src/rviz/default_plugin/markers/mesh_resource_marker.cpp
@@ -82,8 +82,7 @@ void MeshResourceMarker::reset()
     }
   }
   materials_.clear();
-  // the actual passes are deleted by the material
-  color_tint_passes_.clear();
+
 }
 
 void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const MarkerConstPtr& new_message)
@@ -95,6 +94,27 @@ void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const M
 
   scene_node_->setVisible(false);
 
+  // Get the color information from the message
+  float r = new_message->color.r;
+  float g = new_message->color.g;
+  float b = new_message->color.b;
+  float a = new_message->color.a;
+
+  Ogre::SceneBlendType blending;
+  bool depth_write;
+
+  if (a < 0.9998)
+  {
+    blending = Ogre::SBT_TRANSPARENT_ALPHA;
+    depth_write = false;
+  }
+  else
+  {
+    blending = Ogre::SBT_REPLACE;
+    depth_write = true;
+  }
+
+
   if (!entity_ ||
       old_message->mesh_resource != new_message->mesh_resource ||
       old_message->mesh_use_embedded_materials != new_message->mesh_use_embedded_materials)
@@ -124,13 +144,14 @@ void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const M
     std::string id = ss.str();
     entity_ = context_->getSceneManager()->createEntity(id, new_message->mesh_resource);
     scene_node_->attachObject(entity_);
-
+    
     // create a default material for any sub-entities which don't have their own.
     ss << "Material";
     Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME);
     default_material->setReceiveShadows(false);
     default_material->getTechnique(0)->setLightingEnabled(true);
     default_material->getTechnique(0)->setAmbient(0.5, 0.5, 0.5);
+
     materials_.insert(default_material);
 
     if (new_message->mesh_use_embedded_materials)
@@ -171,13 +192,7 @@ void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const M
       entity_->setMaterial(default_material);
     }
 
-    // add a pass to every material to perform the color tinting
-    S_MaterialPtr::iterator material_it;
-    for (material_it = materials_.begin(); material_it != materials_.end(); material_it++)
-    {
-      Ogre::Technique* technique = (*material_it)->getTechnique(0);
-      color_tint_passes_.push_back(technique->createPass());
-    }
+   
 
     // always update color on resource change
     update_color = true;
@@ -203,36 +218,24 @@ void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const M
   //  if the mesh_use_embedded_materials is true and color is non-zero
   //  then the color will be used to tint the embedded materials
   if (update_color)
-  {
-    float r = new_message->color.r;
-    float g = new_message->color.g;
-    float b = new_message->color.b;
-    float a = new_message->color.a;
-
-    Ogre::SceneBlendType blending;
-    bool depth_write;
-
-    if (a < 0.9998)
-    {
-      blending = Ogre::SBT_TRANSPARENT_ALPHA;
-      depth_write = false;
-    }
-    else
+  { 
+    if( new_message->mesh_use_embedded_materials && r == 0 && g == 0 && b == 0 && a == 0 )
     {
-      blending = Ogre::SBT_REPLACE;
-      depth_write = true;
+    blending = Ogre::SBT_REPLACE;
+    depth_write = true;
+    r = 1; g = 1; b = 1; a = 1;
     }
-
-    for (std::vector<Ogre::Pass*>::iterator it = color_tint_passes_.begin();
-         it != color_tint_passes_.end();
-         ++it)
+    S_MaterialPtr::iterator material_it;
+    for (material_it = materials_.begin(); material_it != materials_.end(); material_it++)
     {
-      (*it)->setAmbient(0.5 * r, 0.5 * g, 0.5 * b);
-      (*it)->setDiffuse(r, g, b, a);
-      (*it)->setSceneBlending(blending);
-      (*it)->setDepthWriteEnabled(depth_write);
-      (*it)->setLightingEnabled(true);
+      Ogre::Technique* technique = (*material_it)->getTechnique(0);
+      technique->setAmbient( r*0.5, g*0.5, b*0.5 );
+      technique->setDiffuse( r, g, b, a );
+      technique->setSceneBlending( blending );
+      technique->setDepthWriteEnabled( depth_write );
+      technique->setLightingEnabled( true );
     }
+   
   }
 
   Ogre::Vector3 pos, scale;
@@ -257,4 +260,3 @@ S_MaterialPtr MeshResourceMarker::getMaterials()
 }
 
 }
-
diff --git a/src/rviz/default_plugin/markers/mesh_resource_marker.h b/src/rviz/default_plugin/markers/mesh_resource_marker.h
index 67b8d16..9b60413 100644
--- a/src/rviz/default_plugin/markers/mesh_resource_marker.h
+++ b/src/rviz/default_plugin/markers/mesh_resource_marker.h
@@ -64,8 +64,7 @@ protected:
   //! Scaling factor to convert units. Currently relevant for Collada only.
   float unit_rescale_;
 
-  //! list of passes created for adding color tint to the mesh
-  std::vector<Ogre::Pass*> color_tint_passes_;
+
 };
 
 }
diff --git a/src/rviz/default_plugin/point_cloud_common.cpp b/src/rviz/default_plugin/point_cloud_common.cpp
index 4549d86..527ea4d 100644
--- a/src/rviz/default_plugin/point_cloud_common.cpp
+++ b/src/rviz/default_plugin/point_cloud_common.cpp
@@ -188,17 +188,21 @@ void PointCloudSelectionHandler::createProperties( const Picked& obj, Property*
           {
             continue;
           }
-          if( name == "rgb" )
+          if( name == "rgb" || name == "rgba")
           {
-            uint32_t val = valueFromCloud<uint32_t>( message, f.offset, f.datatype, message->point_step, index );
+            float float_val = valueFromCloud<float>( message, f.offset, f.datatype, message->point_step, index );
+            // Convertion hack because rgb are stored int float (datatype=7) and valueFromCloud can't cast float to uint32_t
+            uint32_t val = *((uint32_t*) &float_val);
             ColorProperty* prop = new ColorProperty( QString( "%1: %2" ).arg( field ).arg( QString::fromStdString( name )),
-                                                     QColor( val >> 16, (val >> 8) & 0xff, val & 0xff ), "", cat );
+                                                     QColor( (val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff), "", cat );
             prop->setReadOnly( true );
+
+            FloatProperty* aprop = new FloatProperty( QString( "alpha" ), ((val >> 24) / 255.0), "", cat );
+            aprop->setReadOnly( true );
           }
           else
           {
             float val = valueFromCloud<float>( message, f.offset, f.datatype, message->point_step, index );
-            
             FloatProperty* prop = new FloatProperty( QString( "%1: %2" ).arg( field ).arg( QString::fromStdString( name )),
                                                      val, "", cat );
             prop->setReadOnly( true );
@@ -439,7 +443,8 @@ void PointCloudCommon::updateAlpha()
 {
   for ( unsigned i=0; i<cloud_infos_.size(); i++ )
   {
-    cloud_infos_[i]->cloud_->setAlpha( alpha_property_->getFloat() );
+    bool per_point_alpha = findChannelIndex(cloud_infos_[i]->message_, "rgba") != -1;
+    cloud_infos_[i]->cloud_->setAlpha( alpha_property_->getFloat(), per_point_alpha );
   }
 }
 
@@ -582,10 +587,12 @@ void PointCloudCommon::update(float wall_dt, float ros_dt)
           continue;
         }
 
+        bool per_point_alpha = findChannelIndex(cloud_info->message_, "rgba") != -1;
+
         cloud_info->cloud_.reset( new PointCloud() );
         cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
         cloud_info->cloud_->setRenderMode( mode );
-        cloud_info->cloud_->setAlpha( alpha_property_->getFloat() );
+        cloud_info->cloud_->setAlpha( alpha_property_->getFloat(), per_point_alpha);
         cloud_info->cloud_->setDimensions( size, size, size );
         cloud_info->cloud_->setAutoSize(auto_size_);
 
@@ -917,11 +924,6 @@ void PointCloudCommon::addMessage(const sensor_msgs::PointCloudConstPtr& cloud)
 
 void PointCloudCommon::addMessage(const sensor_msgs::PointCloud2ConstPtr& cloud)
 {
-  if (cloud->width * cloud->height == 0)
-  {
-    return;
-  }
-
   processMessage(cloud);
 }
 
diff --git a/src/rviz/default_plugin/point_cloud_transformers.cpp b/src/rviz/default_plugin/point_cloud_transformers.cpp
index 5b75507..295858f 100644
--- a/src/rviz/default_plugin/point_cloud_transformers.cpp
+++ b/src/rviz/default_plugin/point_cloud_transformers.cpp
@@ -320,7 +320,7 @@ bool XYZPCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
 
 uint8_t RGB8PCTransformer::supports(const sensor_msgs::PointCloud2ConstPtr& cloud)
 {
-  int32_t index = findChannelIndex(cloud, "rgb");
+  int32_t index = std::max(findChannelIndex(cloud, "rgb"), findChannelIndex(cloud, "rgba"));
   if (index == -1)
   {
     return Support_None;
@@ -343,7 +343,9 @@ bool RGB8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
     return false;
   }
 
-  int32_t index = findChannelIndex(cloud, "rgb");
+  const int32_t rgb  = findChannelIndex(cloud, "rgb");
+  const int32_t rgba = findChannelIndex(cloud, "rgba");
+  const int32_t index = std::max(rgb, rgba);
 
   const uint32_t off = cloud->fields[index].offset;
   uint8_t const* rgb_ptr = &cloud->data.front() + off;
@@ -355,13 +357,27 @@ bool RGB8PCTransformer::transform(const sensor_msgs::PointCloud2ConstPtr& cloud,
   {
     rgb_lut[i] = float(i)/255.0f;
   }
-  for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
+  if (rgb != -1) // rgb
   {
-    uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
-    iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
-    iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
-    iter->color.b = rgb_lut[rgb & 0xff];
-    iter->color.a = 1.0f;
+    for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
+    {
+      uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
+      iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
+      iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
+      iter->color.b = rgb_lut[rgb & 0xff];
+      iter->color.a = 1.0f;
+    }
+  }
+  else // rgba
+  {
+    for (V_PointCloudPoint::iterator iter = points_out.begin(); iter != points_out.end(); ++iter, rgb_ptr += point_step)
+    {
+      uint32_t rgb = *reinterpret_cast<const uint32_t*>(rgb_ptr);
+      iter->color.r = rgb_lut[(rgb >> 16) & 0xff];
+      iter->color.g = rgb_lut[(rgb >> 8) & 0xff];
+      iter->color.b = rgb_lut[rgb & 0xff];
+      iter->color.a = rgb_lut[rgb >> 24];
+    }
   }
 
   return true;
diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp
index e77b073..7671d1f 100644
--- a/src/rviz/default_plugin/tf_display.cpp
+++ b/src/rviz/default_plugin/tf_display.cpp
@@ -469,7 +469,9 @@ void TFDisplay::updateFrame( FrameInfo* frame )
   // Check last received time so we can grey out/fade out frames that have stopped being published
   ros::Time latest_time;
   tf->getLatestCommonTime( fixed_frame_.toStdString(), frame->name_, latest_time, 0 );
-  if( latest_time != frame->last_time_to_fixed_ )
+
+  if(( latest_time != frame->last_time_to_fixed_ ) ||
+     ( latest_time == ros::Time() ))
   {
     frame->last_update_ = ros::Time::now();
     frame->last_time_to_fixed_ = latest_time;
diff --git a/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp b/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp
new file mode 100644
index 0000000..7eb1079
--- /dev/null
+++ b/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.cpp
@@ -0,0 +1,239 @@
+/*
+ * Copyright (c) 2012, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ *     * Redistributions of source code must retain the above copyright
+ *       notice, this list of conditions and the following disclaimer.
+ *     * Redistributions in binary form must reproduce the above copyright
+ *       notice, this list of conditions and the following disclaimer in the
+ *       documentation and/or other materials provided with the distribution.
+ *     * Neither the name of the Willow Garage, Inc. nor the names of its
+ *       contributors may be used to endorse or promote products derived from
+ *       this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <stdint.h>
+
+#include <ros/ros.h>
+
+#include <OgreCamera.h>
+#include <OgrePlane.h>
+#include <OgreQuaternion.h>
+#include <OgreRay.h>
+#include <OgreSceneNode.h>
+#include <OgreVector3.h>
+#include <OgreViewport.h>
+#include <OgreMath.h>
+
+#include "rviz/display_context.h"
+#include "rviz/ogre_helpers/shape.h"
+#include "rviz/properties/float_property.h"
+#include "rviz/properties/vector_property.h"
+#include "rviz/viewport_mouse_event.h"
+
+#include "rviz/default_plugin/view_controllers/third_person_follower_view_controller.h"
+
+namespace rviz
+{
+
+// move camera up so the focal point appears in the lower image half
+static const float CAMERA_OFFSET = 0.2;
+
+void ThirdPersonFollowerViewController::onInitialize()
+{
+  OrbitViewController::onInitialize();
+  focal_shape_->setColor(0.0f, 1.0f, 1.0f, 0.5f);
+}
+
+bool ThirdPersonFollowerViewController::intersectGroundPlane( Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d )
+{
+  //convert rays into reference frame
+  mouse_ray.setOrigin( target_scene_node_->convertWorldToLocalPosition( mouse_ray.getOrigin() ) );
+  mouse_ray.setDirection( target_scene_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY ) * mouse_ray.getDirection() );
+
+  Ogre::Plane ground_plane( Ogre::Vector3::UNIT_Z, 0 );
+
+  std::pair<bool, Ogre::Real> intersection = mouse_ray.intersects(ground_plane);
+  if (!intersection.first)
+  {
+    return false;
+  }
+
+  intersection_3d = mouse_ray.getPoint(intersection.second);
+  return true;
+}
+
+void ThirdPersonFollowerViewController::handleMouseEvent(ViewportMouseEvent& event)
+{
+  if ( event.shift() )
+  {
+    setStatus( "<b>Left-Click:</b> Move X/Y.  <b>Right-Click:</b>: Zoom." );
+  }
+  else
+  {
+    setStatus( "<b>Left-Click:</b> Rotate.  <b>Middle-Click:</b> Move X/Y.  <b>Right-Click:</b>: Move Z.  <b>Shift</b>: More options." );
+  }
+
+  int32_t diff_x = 0;
+  int32_t diff_y = 0;
+
+  bool moved = false;
+  if( event.type == QEvent::MouseButtonPress )
+  {
+    focal_shape_->getRootNode()->setVisible(true);
+    moved = true;
+  }
+  else if( event.type == QEvent::MouseButtonRelease )
+  {
+    focal_shape_->getRootNode()->setVisible(false);
+    moved = true;
+  }
+  else if( event.type == QEvent::MouseMove )
+  {
+    diff_x = event.x - event.last_x;
+    diff_y = event.y - event.last_y;
+    moved = true;
+  }
+
+  if( event.left() && !event.shift() )
+  {
+    setCursor( Rotate3D );
+    yaw( diff_x*0.005 );
+    pitch( -diff_y*0.005 );
+  }
+  else if( event.middle() || (event.left() && event.shift()) )
+  {
+    setCursor( MoveXY );
+    // handle mouse movement
+    int width = event.viewport->getActualWidth();
+    int height = event.viewport->getActualHeight();
+
+    Ogre::Ray mouse_ray = event.viewport->getCamera()->getCameraToViewportRay( event.x / (float) width,
+                                                                               event.y / (float) height );
+
+    Ogre::Ray last_mouse_ray =
+      event.viewport->getCamera()->getCameraToViewportRay( event.last_x / (float) width,
+                                                           event.last_y / (float) height );
+
+    Ogre::Vector3 last_intersect, intersect;
+
+    if( intersectGroundPlane( last_mouse_ray, last_intersect ) &&
+        intersectGroundPlane( mouse_ray, intersect ))
+    {
+      Ogre::Vector3 motion = last_intersect - intersect;
+
+      // When dragging near the horizon, the motion can get out of
+      // control.  This throttles it to an arbitrary limit per mouse
+      // event.
+      float motion_distance_limit = 1; /*meter*/
+      if( motion.length() > motion_distance_limit )
+      {
+        motion.normalise();
+        motion *= motion_distance_limit;
+      }
+
+      focal_point_property_->add( motion );
+      emitConfigChanged();
+    }
+  }
+  else if( event.right() )
+  {
+    setCursor( Zoom );
+    zoom( -diff_y * 0.1 * (distance_property_->getFloat() / 10.0f) );
+  }
+  else
+  {
+    setCursor( event.shift() ? MoveXY : Rotate3D );
+  }
+
+  if( event.wheel_delta != 0 )
+  {
+    int diff = event.wheel_delta;
+    zoom( diff * 0.001 * distance_property_->getFloat() );
+    moved = true;
+  }
+
+  if( moved )
+  {
+    context_->queueRender();
+  }
+}
+
+void ThirdPersonFollowerViewController::mimic( ViewController* source_view )
+{
+  FramePositionTrackingViewController::mimic( source_view );
+
+  Ogre::Camera* source_camera = source_view->getCamera();
+  // do some trigonometry
+  Ogre::Ray camera_dir_ray( source_camera->getRealPosition(), source_camera->getRealDirection() );
+  Ogre::Ray camera_down_ray( source_camera->getRealPosition(), -1.0 * source_camera->getRealUp() );
+
+  Ogre::Vector3 a,b;
+
+  if( intersectGroundPlane( camera_dir_ray, b ) &&
+      intersectGroundPlane( camera_down_ray, a ) )
+  {
+    float l_a = source_camera->getPosition().distance( b );
+    float l_b = source_camera->getPosition().distance( a );
+
+    distance_property_->setFloat(( l_a * l_b ) / ( CAMERA_OFFSET * l_a + l_b ));
+    float distance = distance_property_->getFloat();
+
+    camera_dir_ray.setOrigin( source_camera->getRealPosition() - source_camera->getRealUp() * distance * CAMERA_OFFSET );
+    Ogre::Vector3 new_focal_point;
+    intersectGroundPlane( camera_dir_ray, new_focal_point );
+    focal_point_property_->setVector( new_focal_point );
+
+    calculatePitchYawFromPosition( source_camera->getPosition() - source_camera->getUp() * distance * CAMERA_OFFSET );
+  }
+}
+
+void ThirdPersonFollowerViewController::updateCamera()
+{
+  OrbitViewController::updateCamera();
+  camera_->setPosition( camera_->getPosition() + camera_->getUp() * distance_property_->getFloat() * CAMERA_OFFSET );
+}
+
+void ThirdPersonFollowerViewController::updateTargetSceneNode()
+{
+  if ( FramePositionTrackingViewController::getNewTransform() )
+  {
+    target_scene_node_->setPosition( reference_position_ );
+    Ogre::Radian ref_yaw = reference_orientation_.getRoll( false ); // OGRE camera frame looks along -Z, so they call rotation around Z "roll".
+    Ogre::Quaternion ref_yaw_quat(Ogre::Math::Cos(ref_yaw/2), 0, 0, Ogre::Math::Sin(ref_yaw/2));
+    target_scene_node_->setOrientation( ref_yaw_quat );
+
+    context_->queueRender();
+  }
+}
+
+void ThirdPersonFollowerViewController::lookAt( const Ogre::Vector3& point )
+{
+  Ogre::Vector3 camera_position = camera_->getPosition();
+  Ogre::Vector3 new_focal_point = target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition());
+  new_focal_point.z = 0;
+  distance_property_->setFloat( new_focal_point.distance( camera_position ));
+  focal_point_property_->setVector( new_focal_point );
+
+  calculatePitchYawFromPosition(camera_position);
+}
+
+} // end namespace rviz
+
+#include <pluginlib/class_list_macros.h>
+PLUGINLIB_EXPORT_CLASS( rviz::ThirdPersonFollowerViewController, rviz::ViewController )
diff --git a/src/test/fun_display.h b/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h
similarity index 59%
rename from src/test/fun_display.h
rename to src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h
index 0dcf692..b542273 100644
--- a/src/test/fun_display.h
+++ b/src/rviz/default_plugin/view_controllers/third_person_follower_view_controller.h
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2012, Willow Garage, Inc.
+ * Copyright (c) 2009, Willow Garage, Inc.
  * All rights reserved.
  *
  * Redistribution and use in source and binary forms, with or without
@@ -26,36 +26,52 @@
  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  * POSSIBILITY OF SUCH DAMAGE.
  */
-#ifndef FUN_DISPLAY_H
-#define FUN_DISPLAY_H
 
-#include "rviz/properties/enum_property.h"
-#include "rviz/properties/editable_enum_property.h"
+#ifndef RVIZ_THIRD_PERSON_VIEW_CONTROLLER_H
+#define RVIZ_THIRD_PERSON_VIEW_CONTROLLER_H
 
-#include "rviz/display.h"
+#include "rviz/default_plugin/view_controllers/orbit_view_controller.h"
 
-class FunDisplay: public Display
+#include <OgreVector3.h>
+
+namespace Ogre
+{
+class SceneNode;
+}
+
+namespace rviz
+{
+
+class TfFrameProperty;
+
+/**
+ * \brief Like the orbit view controller, but focal point moves only in the x-y plane.
+ */
+class ThirdPersonFollowerViewController : public OrbitViewController
 {
 Q_OBJECT
 public:
-  FunDisplay();
-
-private Q_SLOTS:
-  void onSizeChanged();
-  void onMasterChanged();
-  void onTimerTick();
-  void onMoodChanged();
-  void makeDances( EditableEnumProperty* property );
-
-private:
-  Property* size_;
-  Property* master_;
-  Property* slave_;
-  Property* dance_;
-  EnumProperty* mood_;
-  int count_;
-
-  static FunDisplay* previous_fun_;
+  virtual void onInitialize();
+
+  virtual void handleMouseEvent(ViewportMouseEvent& evt);
+
+  virtual void lookAt( const Ogre::Vector3& point );
+
+  /** @brief Configure the settings of this view controller to give,
+   * as much as possible, a similar view as that given by the
+   * @a source_view.
+   *
+   * @a source_view must return a valid @c Ogre::Camera* from getCamera(). */
+  virtual void mimic( ViewController* source_view );
+
+protected:
+  virtual void updateCamera();
+
+  virtual void updateTargetSceneNode();
+
+  bool intersectGroundPlane( Ogre::Ray mouse_ray, Ogre::Vector3 &intersection_3d );
 };
 
-#endif // FUN_DISPLAY_H
+}
+
+#endif // RVIZ_VIEW_CONTROLLER_H
diff --git a/src/rviz/default_plugin/wrench_display.cpp b/src/rviz/default_plugin/wrench_display.cpp
index 6a83e68..64f9c3b 100644
--- a/src/rviz/default_plugin/wrench_display.cpp
+++ b/src/rviz/default_plugin/wrench_display.cpp
@@ -35,11 +35,16 @@ namespace rviz
                                      "0 is fully transparent, 1.0 is fully opaque.",
                                      this, SLOT( updateColorAndAlpha() ));
 
-	scale_property_ =
-            new rviz::FloatProperty( "Arrow Scale", 2.0,
-                                     "arrow scale",
+	force_scale_property_ =
+            new rviz::FloatProperty( "Force Arrow Scale", 2.0,
+                                     "force arrow scale",
                                      this, SLOT( updateColorAndAlpha() ));
 
+        torque_scale_property_ =
+            new rviz::FloatProperty( "Torque Arrow Scale", 2.0,
+                                     "torque arrow scale",
+                                     this, SLOT( updateColorAndAlpha() ));            
+
 	width_property_ =
             new rviz::FloatProperty( "Arrow Width", 0.5,
                                      "arrow width",
@@ -75,7 +80,8 @@ namespace rviz
     void WrenchStampedDisplay::updateColorAndAlpha()
     {
         float alpha = alpha_property_->getFloat();
-        float scale = scale_property_->getFloat();
+        float force_scale = force_scale_property_->getFloat();
+        float torque_scale = torque_scale_property_->getFloat();
         float width = width_property_->getFloat();
         Ogre::ColourValue force_color = force_color_property_->getOgreColor();
         Ogre::ColourValue torque_color = torque_color_property_->getOgreColor();
@@ -84,7 +90,8 @@ namespace rviz
 	{
             visuals_[i]->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
             visuals_[i]->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
-            visuals_[i]->setScale( scale );
+            visuals_[i]->setForceScale( force_scale );
+            visuals_[i]->setTorqueScale( torque_scale );
             visuals_[i]->setWidth( width );
 	}
     }
@@ -123,6 +130,12 @@ namespace rviz
 	    return;
 	  }
 
+        if ( position.isNaN() )
+          {
+            ROS_ERROR_THROTTLE(1.0, "Wrench position contains NaNs. Skipping render as long as the position is invalid");
+            return;
+          }
+
         // We are keeping a circular buffer of visual pointers.  This gets
         // the next one, or creates and stores it if the buffer is not full
         boost::shared_ptr<WrenchStampedVisual> visual;
@@ -140,13 +153,15 @@ namespace rviz
 	visual->setFramePosition( position );
 	visual->setFrameOrientation( orientation );
         float alpha = alpha_property_->getFloat();
-        float scale = scale_property_->getFloat();
+        float force_scale = force_scale_property_->getFloat();
+        float torque_scale = torque_scale_property_->getFloat();
         float width = width_property_->getFloat();
         Ogre::ColourValue force_color = force_color_property_->getOgreColor();
         Ogre::ColourValue torque_color = torque_color_property_->getOgreColor();
 	visual->setForceColor( force_color.r, force_color.g, force_color.b, alpha );
 	visual->setTorqueColor( torque_color.r, torque_color.g, torque_color.b, alpha );
-        visual->setScale( scale );
+        visual->setForceScale( force_scale );
+        visual->setTorqueScale( torque_scale );
         visual->setWidth( width );
 
         // And send it to the end of the circular buffer
diff --git a/src/rviz/default_plugin/wrench_display.h b/src/rviz/default_plugin/wrench_display.h
index 38b3500..dbbbe69 100644
--- a/src/rviz/default_plugin/wrench_display.h
+++ b/src/rviz/default_plugin/wrench_display.h
@@ -56,7 +56,7 @@ namespace rviz
 
 	// Property objects for user-editable properties.
         rviz::ColorProperty *force_color_property_, *torque_color_property_;
-        rviz::FloatProperty *alpha_property_, *scale_property_, *width_property_;
+        rviz::FloatProperty *alpha_property_, *force_scale_property_, *torque_scale_property_, *width_property_;
 	rviz::IntProperty *history_length_property_;
     };
 } // end namespace rviz_plugin_tutorials
diff --git a/src/rviz/default_plugin/wrench_visual.cpp b/src/rviz/default_plugin/wrench_visual.cpp
index d24934a..e33276e 100644
--- a/src/rviz/default_plugin/wrench_visual.cpp
+++ b/src/rviz/default_plugin/wrench_visual.cpp
@@ -50,15 +50,15 @@ namespace rviz
     {
         Ogre::Vector3 force(msg->wrench.force.x, msg->wrench.force.y, msg->wrench.force.z);
         Ogre::Vector3 torque(msg->wrench.torque.x, msg->wrench.torque.y, msg->wrench.torque.z);
-        double force_length = force.length() * scale_;
-        double torque_length = torque.length() * scale_;
+        double force_length = force.length() * force_scale_;
+        double torque_length = torque.length() * torque_scale_;
 	arrow_force_->setScale(Ogre::Vector3(force_length, width_, width_)); 
 	arrow_torque_->setScale(Ogre::Vector3(torque_length, width_, width_));
 
         arrow_force_->setDirection(force);
         arrow_torque_->setDirection(torque);
         Ogre::Vector3 axis_z(0,0,1);
-        Ogre::Quaternion orientation(axis_z.angleBetween(torque), axis_z.crossProduct(torque.normalisedCopy()));
+        Ogre::Quaternion orientation = axis_z.getRotationTo(torque);
         if ( std::isnan(orientation.x) ||
              std::isnan(orientation.y) ||
              std::isnan(orientation.z) ) orientation = Ogre::Quaternion::IDENTITY;
@@ -100,11 +100,19 @@ namespace rviz
 	circle_arrow_torque_->setColor( r, g, b, a );
     }
 
-    void  WrenchStampedVisual::setScale( float s ) {
-      scale_ = s;
+    void  WrenchStampedVisual::setForceScale( float s )
+    {
+        force_scale_ = s;
+    }
+
+    void  WrenchStampedVisual::setTorqueScale( float s )
+    {
+        torque_scale_ = s;
     }
-    void  WrenchStampedVisual::setWidth( float w ) {
-      width_ = w;
+
+    void  WrenchStampedVisual::setWidth( float w )
+    {
+        width_ = w;
     }
 
 } // end namespace rviz
diff --git a/src/rviz/default_plugin/wrench_visual.h b/src/rviz/default_plugin/wrench_visual.h
index f828aea..2215922 100644
--- a/src/rviz/default_plugin/wrench_visual.h
+++ b/src/rviz/default_plugin/wrench_visual.h
@@ -48,7 +48,8 @@ public:
     // parameters and therefore don't come from the WrenchStamped message.
     void setForceColor( float r, float g, float b, float a );
     void setTorqueColor( float r, float g, float b, float a );
-    void setScale( float s );
+    void setForceScale( float s );
+    void setTorqueScale( float s );
     void setWidth( float w );
 
 private:
@@ -57,7 +58,7 @@ private:
     rviz::Arrow* arrow_torque_;
     rviz::BillboardLine* circle_torque_;
     rviz::Arrow* circle_arrow_torque_;
-    float scale_, width_;
+    float force_scale_, torque_scale_, width_;
 
     // A SceneNode whose pose is set to match the coordinate frame of
     // the WrenchStamped message header.
diff --git a/src/rviz/display.cpp b/src/rviz/display.cpp
index bb46f94..12c2264 100644
--- a/src/rviz/display.cpp
+++ b/src/rviz/display.cpp
@@ -86,7 +86,7 @@ void Display::initialize( DisplayContext* context )
   context_ = context;
   scene_manager_ = context_->getSceneManager();
   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
-  
+
   update_nh_.setCallbackQueue( context_->getUpdateQueue() );
   threaded_nh_.setCallbackQueue( context_->getThreadedQueue() );
   fixed_frame_ = context_->getFixedFrame();
diff --git a/src/rviz/frame_position_tracking_view_controller.cpp b/src/rviz/frame_position_tracking_view_controller.cpp
index 1596b24..ff1943b 100644
--- a/src/rviz/frame_position_tracking_view_controller.cpp
+++ b/src/rviz/frame_position_tracking_view_controller.cpp
@@ -92,18 +92,26 @@ void FramePositionTrackingViewController::updateTargetFrame()
   onTargetFrameChanged( old_position, old_orientation );
 }
 
-void FramePositionTrackingViewController::updateTargetSceneNode()
+bool FramePositionTrackingViewController::getNewTransform()
 {
   Ogre::Vector3 new_reference_position;
   Ogre::Quaternion new_reference_orientation;
 
-  if( context_->getFrameManager()->getTransform( target_frame_property_->getFrameStd(), ros::Time(),
-                                                 new_reference_position, new_reference_orientation ))
+  bool got_transform = context_->getFrameManager()->getTransform( target_frame_property_->getFrameStd(), ros::Time(),
+        new_reference_position, new_reference_orientation );
+  if( got_transform )
   {
-    target_scene_node_->setPosition( new_reference_position );
-
     reference_position_ = new_reference_position;
     reference_orientation_ = new_reference_orientation;
+  }
+  return got_transform;
+}
+
+void FramePositionTrackingViewController::updateTargetSceneNode()
+{
+  if ( getNewTransform() )
+  {
+    target_scene_node_->setPosition( reference_position_ );
 
     context_->queueRender();
   }
@@ -119,6 +127,7 @@ void FramePositionTrackingViewController::updateTargetSceneNode()
 /////    // target_prop->setToOK();
 /////    global_status_->setStatus( StatusProperty::Ok, "Target Frame", "OK" );
 /////  }
+
 }
 
 void FramePositionTrackingViewController::mimic( ViewController* source_view )
diff --git a/src/rviz/frame_position_tracking_view_controller.h b/src/rviz/frame_position_tracking_view_controller.h
index f76d2e8..5fdfc94 100644
--- a/src/rviz/frame_position_tracking_view_controller.h
+++ b/src/rviz/frame_position_tracking_view_controller.h
@@ -86,9 +86,11 @@ protected:
    * @see updateTargetFrame() */
   virtual void onTargetFrameChanged( const Ogre::Vector3& old_reference_position, const Ogre::Quaternion& old_reference_orientation ) {}
 
+  bool getNewTransform();
+
   /** @brief Update the position of the target_scene_node_ from the TF
    * frame specified in the Target Frame property. */
-  void updateTargetSceneNode();
+  virtual void updateTargetSceneNode();
 
   TfFrameProperty* target_frame_property_;
   Ogre::SceneNode* target_scene_node_;
diff --git a/src/rviz/mesh_loader.cpp b/src/rviz/mesh_loader.cpp
index 76c29f0..c598065 100644
--- a/src/rviz/mesh_loader.cpp
+++ b/src/rviz/mesh_loader.cpp
@@ -713,7 +713,7 @@ Ogre::MeshPtr loadMeshFromResource(const std::string& resource_path)
       }
 
       ogre_tools::STLLoader loader;
-      if (!loader.load(res.data.get()))
+      if (!loader.load(res.data.get(), res.size, resource_path))
       {
         ROS_ERROR("Failed to load file [%s]", resource_path.c_str());
         return Ogre::MeshPtr();
diff --git a/src/rviz/ogre_helpers/stl_loader.cpp b/src/rviz/ogre_helpers/stl_loader.cpp
index 5ef2d57..6583b17 100644
--- a/src/rviz/ogre_helpers/stl_loader.cpp
+++ b/src/rviz/ogre_helpers/stl_loader.cpp
@@ -71,26 +71,87 @@ bool STLLoader::load(const std::string& path)
   // find the file size
   fseek( input, 0, SEEK_END );
   long fileSize = ftell( input );
-  fseek( input, 0, SEEK_SET );
+  rewind( input );
 
-  uint8_t* buffer = new uint8_t[ fileSize ];
-  long num_bytes_read = fread( buffer, fileSize, 1, input );
-  if( num_bytes_read != fileSize )
+  std::vector<uint8_t> buffer_vec(fileSize);
+  uint8_t* buffer = &buffer_vec[0];
+
+  long num_bytes_read = fread( buffer, 1, fileSize, input );
+  if ( num_bytes_read != fileSize )
   {
-    ROS_ERROR( "STLLoader::load( \"%s\" ) only read %ld bytes out of total %ld.",
-               path.c_str(), num_bytes_read, fileSize );
+    ROS_ERROR("STLLoader::load( \"%s\" ) only read %ld bytes out of total %ld.",
+              path.c_str(), num_bytes_read, fileSize);
+    fclose( input );
+    return false;
   }
   fclose( input );
 
-  bool success = load(buffer);
-  delete [] buffer;
+  return this->load(buffer, num_bytes_read, path);
+}
+
+bool STLLoader::load(uint8_t* buffer, const size_t num_bytes, const std::string& origin)
+{
+  // check for ascii since we can only load binary types with this class
+  std::string buffer_str = std::string(reinterpret_cast<char *>(buffer), num_bytes);
 
-  return success;
+  if (buffer_str.substr(0, 5) == std::string("solid"))
+  {
+    // file says that it is ascii, but why should we trust it?
+
+    // check for "endsolid" as well
+    if (buffer_str.find("endsolid", 5) != std::string::npos)
+    {
+      ROS_ERROR_STREAM("The STL file '" << origin << "' is malformed. It "
+                       "starts with the word 'solid' and also contains the "
+                       "word 'endsolid', indicating that it's an ASCII STL "
+                       "file, but rviz can only load binary STL files so it "
+                       "will not be loaded. Please convert it to a "
+                       "binary STL file.");
+      return false;
+    }
+
+    // chastise the user for malformed files
+    ROS_WARN_STREAM("The STL file '" << origin << "' is malformed. It starts"
+                    " with the word 'solid', indicating that it's an ASCII "
+                    "STL file, but it does not contain the word 'endsolid' so"
+                    "it is either a malformed ASCII STL file or it is actually "
+                    "a binary STL file. Trying to interpret it as a binary "
+                    "STL file instead.");
+  }
+
+  // make sure there's enough data for a binary STL header and triangle count
+  static const size_t binary_stl_header_len = 84;
+  if (num_bytes <= binary_stl_header_len)
+  {
+    ROS_ERROR_STREAM("The STL file '" << origin <<"' is malformed. It "
+                     "appears to be a binary STL file but does not contain "
+                     "enough data for the 80 byte header and 16-bit integer "
+                     "triangle count.");
+    return false;
+  }
+
+  // one last check to make sure that the size matches the number of triangles
+  unsigned int num_triangles = *(reinterpret_cast<uint16_t *>(buffer + 80));
+  static const size_t number_of_bytes_per_triangle = 50;
+  size_t expected_size = binary_stl_header_len + num_triangles * number_of_bytes_per_triangle;
+  if (num_bytes != expected_size)
+  {
+    ROS_ERROR_STREAM("The STL file '" << origin << "' is malformed. According "
+                     "to the binary STL header it should have '" <<
+                     num_triangles << "' triangles, but it has too " <<
+                     (num_bytes > expected_size ? "much" : "little") <<
+                     " data for that to be the case.");
+    return false;
+  }
+
+  // load the binary STL data
+  return this->load_binary(buffer);
 }
 
-bool STLLoader::load(uint8_t* buffer)
+bool STLLoader::load_binary(uint8_t* buffer)
 {
   uint8_t* pos = buffer;
+
   pos += 80; // skip the 80 byte header
 
   unsigned int numTriangles = *(unsigned int*)pos;
diff --git a/src/rviz/ogre_helpers/stl_loader.h b/src/rviz/ogre_helpers/stl_loader.h
index ccc6d88..8268fee 100644
--- a/src/rviz/ogre_helpers/stl_loader.h
+++ b/src/rviz/ogre_helpers/stl_loader.h
@@ -46,7 +46,7 @@ public:
   ~STLLoader();
 
   bool load(const std::string& path);
-  bool load(uint8_t* buffer);
+  bool load(uint8_t* buffer, const size_t num_bytes, const std::string& origin);
 
   Ogre::MeshPtr toMesh(const std::string& name);
 
@@ -58,6 +58,10 @@ public:
 
   typedef std::vector<Triangle> V_Triangle;
   V_Triangle triangles_;
+
+protected:
+  //! Load a binary STL file
+  bool load_binary(uint8_t* buffer);
 };
 
 }
diff --git a/src/rviz/robot/robot.cpp b/src/rviz/robot/robot.cpp
index 5d00476..a65c129 100644
--- a/src/rviz/robot/robot.cpp
+++ b/src/rviz/robot/robot.cpp
@@ -735,6 +735,43 @@ void Robot::update(const LinkUpdater& updater)
                                    collision_position, collision_orientation
                                    ))
     {
+      // Check if visual_orientation, visual_position, collision_orientation, and collision_position are NaN.
+      if (visual_orientation.isNaN())
+      {
+        ROS_ERROR_THROTTLE(
+          1.0,
+          "visual orientation of %s contains NaNs. Skipping render as long as the orientation is invalid.",
+          link->getName().c_str()
+        );
+        continue;
+      }
+      if (visual_position.isNaN())
+      {
+        ROS_ERROR_THROTTLE(
+          1.0,
+          "visual position of %s contains NaNs. Skipping render as long as the position is invalid.",
+          link->getName().c_str()
+        );
+        continue;
+      }
+      if (collision_orientation.isNaN())
+      {
+        ROS_ERROR_THROTTLE(
+          1.0,
+          "collision orientation of %s contains NaNs. Skipping render as long as the orientation is invalid.",
+          link->getName().c_str()
+        );
+        continue;
+      }
+      if (collision_position.isNaN())
+      {
+        ROS_ERROR_THROTTLE(
+          1.0,
+          "collision position of %s contains NaNs. Skipping render as long as the position is invalid.",
+          link->getName().c_str()
+        );
+        continue;
+      }
       link->setTransforms( visual_position, visual_orientation, collision_position, collision_orientation );
 
       std::vector<std::string>::const_iterator joint_it = link->getChildJointNames().begin();
diff --git a/src/rviz/visualization_frame.cpp b/src/rviz/visualization_frame.cpp
index 5d52db5..6d04993 100644
--- a/src/rviz/visualization_frame.cpp
+++ b/src/rviz/visualization_frame.cpp
@@ -150,6 +150,7 @@ VisualizationFrame::VisualizationFrame( QWidget* parent )
   fps_label_->setMinimumWidth(40);
   fps_label_->setAlignment(Qt::AlignRight);
   statusBar()->addPermanentWidget( fps_label_, 0 );
+  original_status_bar_ = statusBar();
 
   setWindowTitle( "RViz[*]" );
 }
@@ -182,7 +183,10 @@ void VisualizationFrame::updateFps()
     float fps = frame_count_ / wall_diff.toSec();
     frame_count_ = 0;
     last_fps_calc_time_ = ros::WallTime::now();
-    fps_label_->setText( QString::number(int(fps)) + QString(" fps") );
+    if ( original_status_bar_ == statusBar() )
+    {
+      fps_label_->setText( QString::number(int(fps)) + QString(" fps") );
+    }
   }
 }
 
diff --git a/src/rviz/visualization_frame.h b/src/rviz/visualization_frame.h
index 264017f..3a5708e 100644
--- a/src/rviz/visualization_frame.h
+++ b/src/rviz/visualization_frame.h
@@ -340,6 +340,7 @@ protected:
 
   QLabel* status_label_;
   QLabel* fps_label_;
+  QStatusBar* original_status_bar_;
 
   int frame_count_;
   ros::WallTime last_fps_calc_time_;
diff --git a/src/rviz/visualizer_app.cpp b/src/rviz/visualizer_app.cpp
index f903be5..cef8ea3 100644
--- a/src/rviz/visualizer_app.cpp
+++ b/src/rviz/visualizer_app.cpp
@@ -44,6 +44,7 @@
 #undef check
 #endif
 
+#include <ros/console.h>
 #include <ros/ros.h>
 
 #include "rviz/selection/selection_manager.h"
@@ -134,14 +135,15 @@ bool VisualizerApp::init( int argc, char** argv )
       ("in-mc-wrapper", "Signal that this is running inside a master-chooser wrapper")
       ("opengl", po::value<int>(), "Force OpenGL version (use '--opengl 210' for OpenGL 2.1 compatibility mode)")
       ("no-stereo", "Disable the use of stereo rendering.")
-      ("verbose,v", "Enable debug visualizations");
+      ("verbose,v", "Enable debug visualizations")
+      ("log-level-debug", "Sets the ROS logger level to debug.");
     po::variables_map vm;
     std::string display_config, fixed_frame, splash_path, help_path;
     bool enable_ogre_log = false;
     bool in_mc_wrapper = false;
     bool verbose = false;
     int force_gl_version = 0;
-	bool disable_stereo = false;
+    bool disable_stereo = false;
     try
     {
       po::store( po::parse_command_line( argc, argv, options ), vm );
@@ -205,6 +207,14 @@ bool VisualizerApp::init( int argc, char** argv )
       {
         verbose = true;
       }
+
+      if (vm.count("log-level-debug"))
+      {
+        if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) )
+        {
+          ros::console::notifyLoggerLevelsChanged();
+        }
+      }
     }
     catch (std::exception& e)
     {
diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt
index 5d40073..2c38c3b 100644
--- a/src/test/CMakeLists.txt
+++ b/src/test/CMakeLists.txt
@@ -1,140 +1,151 @@
-message("TODO: convert rviz tests to catkin.")
+# rviz's automated tests
+find_package(rostest REQUIRED)
 
+# This is a test utility which publishes images of different types.
 add_executable(send_images EXCLUDE_FROM_ALL send_images.cpp)
 target_link_libraries(send_images ${catkin_LIBRARIES})
 add_dependencies(tests send_images)
 
+# This is a test utility which can publish different kinds of markers.
 add_executable(marker_test EXCLUDE_FROM_ALL marker_test.cpp)
 target_link_libraries(marker_test ${catkin_LIBRARIES})
 add_dependencies(tests marker_test)
 
+# This is a test utility which can publish different kinds of mesh markers.
 add_executable(mesh_marker_test EXCLUDE_FROM_ALL mesh_marker_test.cpp)
 target_link_libraries(mesh_marker_test ${catkin_LIBRARIES})
 add_dependencies(tests mesh_marker_test)
 
+# This is a GTest which tests the different types of primitive display properties.
+qt4_wrap_cpp(MOC_MOCK_PROPERTY_CHANGE_RECEIVER mock_property_change_receiver.h)
+catkin_add_gtest(property_test
+  property_test.cpp
+  mock_property_change_receiver.cpp
+  ${MOC_MOCK_PROPERTY_CHANGE_RECEIVER}
+)
+target_link_libraries(property_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 
+# TODO(wjwwood): Fix this test, it used to use a set of Mock classes, but
+#                has since undergone a lot of changes and it no longer works.
+# This is a GTest which tests the display system.
+# qt4_wrap_cpp(MOC_MOCK_DISPLAY mock_display.h)
+# add_rostest_gtest(display_test display_test.test
+#   display_test.cpp
+#   mock_context.cpp
+#   mock_display.cpp
+#   mock_display_factory.cpp
+#   mock_property_change_receiver.cpp
+#   ${MOC_MOCK_DISPLAY}
+#   ${MOC_MOCK_PROPERTY_CHANGE_RECEIVER}
+# )
+# target_link_libraries(display_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
 
-##   qt4_wrap_cpp(MOC_MOCK_PROPERTY_CHANGE_RECEIVER
-##     mock_property_change_receiver.h
-##   )
-##   rosbuild_add_gtest(property_test
-##     property_test.cpp
-##     mock_property_change_receiver.cpp
-##     ${MOC_MOCK_PROPERTY_CHANGE_RECEIVER}
-##   )
-##   target_link_libraries(property_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   
-##   qt4_wrap_cpp(MOC_MOCK_DISPLAY
-##     mock_display.h
-##   )
-##   rosbuild_add_gtest(display_test
-##     display_test.cpp
-##     mock_context.cpp
-##     mock_display.cpp
-##     mock_display_factory.cpp
-##     mock_property_change_receiver.cpp
-##     ${MOC_MOCK_DISPLAY}
-##     ${MOC_MOCK_PROPERTY_CHANGE_RECEIVER}
-##   )
-##   target_link_libraries(display_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   
-##   # qt4_wrap_cpp(MOC_PLAYGROUND
-##   #   mock_display.h
-##   #   playground.h
-##   #   fun_display.h
-##   # )
-##   # rosbuild_add_executable(playground
-##   #   playground.cpp
-##   #   fun_display.cpp
-##   #   mock_display.cpp
-##   #   mock_display_factory.cpp
-##   #   ${MOC_PLAYGROUND}
-##   # )
-##   # target_link_libraries(playground ${PROJECT_NAME} ${QT_LIBRARIES})
-##   
-##   ## rosbuild_add_gtest(uniform_string_stream_test uniform_string_stream_test.cpp ../rviz/uniform_string_stream.cpp)
-##   ## 
-##   rosbuild_add_executable(marker_test marker_test.cpp)
-##   rosbuild_declare_test(marker_test)
-##   
-##   rosbuild_add_executable(rviz_logo_marker EXCLUDE_FROM_ALL rviz_logo_marker.cpp)
-##   rosbuild_add_executable(cloud_test EXCLUDE_FROM_ALL cloud_test.cpp)
-##   
-##   
-##   #rosbuild_add_executable(interactive_marker_test interactive_marker_test.cpp)
-##   #rosbuild_declare_test(interactive_marker_test)
-##   
-##   ## # rosbuild_add_executable(cloud_test EXCLUDE_FROM_ALL cloud_test.cpp)
-##   ## # rosbuild_declare_test(cloud_test)
-##   ## # rosbuild_add_executable(image_test EXCLUDE_FROM_ALL image_test.cpp)
-##   ## # rosbuild_declare_test(image_test)
-##   ## # 
-##   ## rosbuild_add_gtest(interactive_marker_client_test
-##   ##   interactive_marker_client_test.cpp
-##   ##   ../rviz/default_plugin/interactive_markers/interactive_marker_client.cpp)
-##   ##  
+# This is a GTest which tests the uniform_string_stream.
+catkin_add_gtest(uniform_string_stream_test
+  uniform_string_stream_test.cpp
+  ../rviz/uniform_string_stream.cpp
+)
+
+# This is an example node which serves an rviz logo as an interactive marker.
+add_executable(rviz_logo_marker EXCLUDE_FROM_ALL rviz_logo_marker.cpp)
+target_link_libraries(rviz_logo_marker ${catkin_LIBRARIES})
+add_dependencies(tests rviz_logo_marker)
+
+# This is an example node which publishes different kinds of point clouds.
+add_executable(cloud_test EXCLUDE_FROM_ALL cloud_test.cpp)
+target_link_libraries(cloud_test ${catkin_LIBRARIES})
+add_dependencies(tests cloud_test)
+
+# This is an example node which serves an interactive marker.
+add_executable(interactive_marker_test interactive_marker_test.cpp)
+target_link_libraries(interactive_marker_test ${catkin_LIBRARIES})
+add_dependencies(tests interactive_marker_test)
+
+# This is another example node that publishes images.
+add_executable(image_test EXCLUDE_FROM_ALL image_test.cpp)
+target_link_libraries(image_test ${catkin_LIBRARIES})
+add_dependencies(tests image_test)
+
+# This is a node that sends lots of point clouds.
 add_executable(send_lots_of_points EXCLUDE_FROM_ALL send_lots_of_points_node.cpp)
 target_link_libraries(send_lots_of_points ${catkin_LIBRARIES})
 add_dependencies(tests send_lots_of_points)
 
+# Yet another example which sends point clouds.
 add_executable(send_point_cloud_2 EXCLUDE_FROM_ALL send_point_cloud_2.cpp)
 target_link_libraries(send_point_cloud_2 ${catkin_LIBRARIES})
 add_dependencies(tests send_point_cloud_2)
 
+# This is a node which sends grid cells.
 add_executable(send_grid_cells EXCLUDE_FROM_ALL send_grid_cells_node.cpp)
 target_link_libraries(send_grid_cells ${catkin_LIBRARIES})
 add_dependencies(tests send_grid_cells)
 
-##   ## rosbuild_add_executable(vis_panel_example vis_panel_example.cpp)
-##   ## target_link_libraries(vis_panel_example ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(vis_panel_example)
-##   ## 
-##   ## rosbuild_add_executable(render_panel_test render_panel_test.cpp)
-##   ## target_link_libraries(render_panel_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(render_panel_test)
-##   ## 
-##   ## rosbuild_add_executable(new_display_dialog_test new_display_dialog_test.cpp)
-##   ## target_link_libraries(new_display_dialog_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(new_display_dialog_test)
-##   ## 
-##   ## rosbuild_add_executable(color_editor_test color_editor_test.cpp)
-##   ## target_link_libraries(color_editor_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(color_editor_test)
-##   ## 
-##   ## qt4_wrap_cpp(PROPERTY_TEST_MOC_FILES
-##   ##   ros_spinner.h
-##   ##   )
-##   ## rosbuild_add_executable(property_test property_test.cpp ros_spinner.cpp ${PROPERTY_TEST_MOC_FILES})
-##   ## target_link_libraries(property_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(property_test)
-##   ## 
-##   ## rosbuild_add_gtest(topic_info_variant_test topic_info_variant_test.cpp)
-##   ## target_link_libraries(topic_info_variant_test ${QT_LIBRARIES})
-##   ## 
-##   ## rosbuild_add_executable(line_edit_with_button_test line_edit_with_button_test.cpp)
-##   ## target_link_libraries(line_edit_with_button_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(line_edit_with_button_test)
-##   ## 
-##   ## rosbuild_add_executable(topic_dialog_test topic_dialog_test.cpp)
-##   ## target_link_libraries(topic_dialog_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(topic_dialog_test)
-##   ## 
-##   ## qt4_wrap_cpp(MOC_FILES
-##   ##   connect_test.h
-##   ##   )
-##   ## rosbuild_add_executable(connect_test connect_test.cpp ${MOC_FILES})
-##   ## target_link_libraries(connect_test ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(connect_test)
-##   ## 
-##   ## rosbuild_add_gtest(config_test config_test.cpp ../rviz/uniform_string_stream.cpp ../rviz/config.cpp)
-##   ## 
-##   ## qt4_wrap_cpp(RENDER_POINTS_TEST_MOC_FILES
-##   ##   render_points_test.h
-##   ##   )
-##   ## rosbuild_add_executable(render_points_test render_points_test.cpp ../rviz/ogre_helpers/orbit_camera.cpp ${RENDER_POINTS_TEST_MOC_FILES})
-##   ## target_link_libraries(render_points_test ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(render_points_test)
-##   ## 
-##   ## rosbuild_add_executable(two_render_widgets two_render_widgets.cpp)
-##   ## target_link_libraries(two_render_widgets ${PROJECT_NAME} ${QT_LIBRARIES})
-##   ## rosbuild_declare_test(two_render_widgets)
+# This is a test program that uses the rviz panel interface.
+add_executable(render_panel_test render_panel_test.cpp)
+target_link_libraries(render_panel_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests render_panel_test)
+
+# This is an executable which uses the rviz new display diaglog interface.
+add_executable(new_display_dialog_test new_display_dialog_test.cpp)
+target_link_libraries(new_display_dialog_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests new_display_dialog_test)
+
+# This is an executable which uses the rviz color editor test.
+add_executable(color_editor_test color_editor_test.cpp)
+target_link_libraries(color_editor_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests color_editor_test)
+
+# This is a modified version of the property test.
+qt4_wrap_cpp(PROPERTY_TEST_MOC_FILES
+  ros_spinner.h
+)
+catkin_add_gtest(property_with_ros_spinner_test
+  property_test.cpp
+  ros_spinner.cpp
+  mock_property_change_receiver.cpp
+  ${PROPERTY_TEST_MOC_FILES}
+  ${MOC_MOCK_PROPERTY_CHANGE_RECEIVER}
+)
+target_link_libraries(property_with_ros_spinner_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests property_with_ros_spinner_test)
+
+# This is an executable that uses the line_edit_with_button property interface.
+add_executable(line_edit_with_button_test line_edit_with_button_test.cpp)
+target_link_libraries(line_edit_with_button_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests line_edit_with_button_test)
+
+# This is an executable which tests the connect/disconnect behavior of signals and slots in Qt.
+qt4_wrap_cpp(MOC_FILES
+  connect_test.h
+)
+add_executable(connect_test connect_test.cpp ${MOC_FILES})
+target_link_libraries(connect_test ${QT_LIBRARIES})
+add_dependencies(tests connect_test)
+
+# This is a GTest which tests the display configuration.
+catkin_add_gtest(config_test config_test.cpp ../rviz/uniform_string_stream.cpp ../rviz/config.cpp)
+target_link_libraries(config_test ${QT_LIBRARIES})
+
+# This is an acceptance test executable which renders points.
+qt4_wrap_cpp(RENDER_POINTS_TEST_MOC_FILES
+  render_points_test.h
+)
+add_executable(render_points_test
+  render_points_test.cpp
+  ../rviz/ogre_helpers/orbit_camera.cpp
+  ${RENDER_POINTS_TEST_MOC_FILES}
+)
+target_link_libraries(render_points_test rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests render_points_test)
+
+# This is an example application which creates two ogre render windows.
+add_executable(two_render_widgets two_render_widgets.cpp)
+target_link_libraries(two_render_widgets rviz ${catkin_LIBRARIES} ${QT_LIBRARIES})
+add_dependencies(tests two_render_widgets)
+
+# This is a GTest which tests the STL loader
+catkin_add_gtest(stl_loader_test stl_loader_test.cpp
+  ../rviz/ogre_helpers/stl_loader.cpp)
+target_link_libraries(stl_loader_test ${catkin_LIBRARIES} ${OGRE_OV_LIBRARIES_ABS})
+
diff --git a/src/test/config_test.cpp b/src/test/config_test.cpp
index 452065b..5843815 100644
--- a/src/test/config_test.cpp
+++ b/src/test/config_test.cpp
@@ -32,241 +32,45 @@
 
 #include <ros/package.h> // For ros::package::getPath()
 
-TEST( Config, comparison )
-{
-  std::string lhs = "b/c/d";
-  std::string rhs = "b/c_d";
-  rviz::Config::DirectoryCompare dc;
-  EXPECT_FALSE( dc( lhs, rhs ));
-}
-
 TEST( Config, set_then_get )
 {
   rviz::Config c;
-  c.set( "a", "1" );
+  c.mapSetValue( "a", "1" );
   int a;
-  EXPECT_TRUE( c.get( "a", &a, 2 ));
+  EXPECT_TRUE( c.mapGetInt( "a", &a ));
   EXPECT_EQ( a, 1 );
   float aa;
-  EXPECT_TRUE( c.get( "a", &aa, 2.0 ));
+  EXPECT_TRUE( c.mapGetFloat( "a", &aa ));
   EXPECT_EQ( aa, 1.0 );
-  std::string aaa;
-  EXPECT_TRUE( c.get( "a", &aaa, "two" ));
+  QString aaa;
+  EXPECT_TRUE( c.mapGetString( "a", &aaa));
   EXPECT_EQ( aaa, "1" );
 }
 
 TEST( Config, parse_floats )
 {
   rviz::Config c;
-  c.set( "f", "1.1" );
+  c.mapSetValue( "f", "1.1" );
   float f;
-  EXPECT_TRUE( c.get( "f", &f, 2.0f ));
+  EXPECT_TRUE( c.mapGetFloat( "f", &f ));
   EXPECT_EQ( f, 1.1f );
 
   // In Europe they use "," for a decimal point.
-  c.set( "f", "1,2" );
-  EXPECT_TRUE( c.get( "f", &f, 2.0f ));
+  c.mapSetValue( "f", "1,2" );
+  EXPECT_TRUE( c.mapGetFloat( "f", &f ));
   EXPECT_EQ( f, 1.2f );
-
-  // This test should pass in all locales because Config uses
-  // UniformStringStream which forces output in the "C" locale.
-  std::string str;
-  c.set( "f", 1.2f );
-  c.get( "f", &str, "chub" );
-  EXPECT_EQ( str, "1.2" );
-}
-
-TEST( Config, default_values )
-{
-  rviz::Config c;
-  int a;
-  EXPECT_FALSE( c.get( "a", &a, 2 ));
-  EXPECT_EQ( a, 2 );
-  EXPECT_FALSE( c.get( "a", &a ));
-  EXPECT_EQ( a, 0 );
-  float aa;
-  EXPECT_FALSE( c.get( "a", &aa, 2.0 ));
-  EXPECT_EQ( aa, 2.0 );
-  EXPECT_FALSE( c.get( "a", &aa ));
-  EXPECT_EQ( aa, 0.0 );
-  std::string aaa;
-  EXPECT_FALSE( c.get( "a", &aaa, "two" ));
-  EXPECT_EQ( aaa, "two" );
-  EXPECT_FALSE( c.get( "a", &aaa ));
-  EXPECT_EQ( aaa, "" );
-}
-
-TEST( Config, write_empty_string_value )
-{
-  rviz::Config c;
-  c.set( "key", "" );
-
-  std::stringstream ss;
-  c.write( ss );
-
-  EXPECT_EQ( "key=\n", ss.str() );
-}
-
-TEST( Config, read_empty_string_value )
-{
-  std::istringstream ss( "key=\n" );
-
-  rviz::Config c;
-  c.read( ss );
-
-  std::string s;
-  EXPECT_TRUE( c.get( "key", &s, "default" ));
-  EXPECT_EQ( "", s );
 }
 
 TEST( Config, set_get_empty_value )
 {
   rviz::Config c;
-  c.set( "key", "" );
+  c.mapSetValue( "key", "" );
 
-  std::string s;
-  EXPECT_TRUE( c.get( "key", &s, "default" ));
+  QString s;
+  EXPECT_TRUE( c.mapGetString( "key", &s ));
   EXPECT_EQ( "", s );
 }
 
-TEST( Config, write )
-{
-  rviz::Config c;
-  c.set( "/b/c_d", 1 );
-  c.set( "b/alpha", 2 );
-  c.set( "z", 6 );
-  c.set( "/a/z", 3 );
-  c.set( "d", 7 );
-  c.set( "/b/c/d", 4);
-  c.set( "/a", 5 );
-  c.set( "/art/for/arts/sake", 8 );
-  std::stringstream ss;
-  c.write( ss );
-  EXPECT_EQ( 
-"a=5\n\
-d=7\n\
-z=6\n\
-[a]\n\
-z=3\n\
-[art]\n\
-[art/for]\n\
-[art/for/arts]\n\
-sake=8\n\
-[b]\n\
-alpha=2\n\
-c_d=1\n\
-[b/c]\n\
-d=4\n\
-", ss.str() );
-}
-
-TEST( Config, read )
-{
-  std::string input =
-"a=1\n\
-foo_bar=biff=1; bazz=17\n\
-[chub]\n\
-sand=wich\n\
-[chub/town]\n\
-belly=big\n\
-tummy=large\n\
-";
-  std::istringstream iss;
-  iss.str( input );
-  rviz::Config c;
-  c.read( iss );
-
-  std::string s;
-  EXPECT_TRUE( c.get( "/chub/town/belly", &s ));
-  EXPECT_EQ( "big", s );
-
-  EXPECT_TRUE( c.get( "/chub/sand", &s ));
-  EXPECT_EQ( "wich", s );
-
-  EXPECT_TRUE( c.get( "/foo_bar", &s ));
-  EXPECT_EQ( "biff=1; bazz=17", s );
-
-  int i;
-  EXPECT_TRUE( c.get( "/a", &i ));
-  EXPECT_EQ( 1, i );
-}
-
-TEST( Config, escape_space )
-{
-  rviz::Config c;
-  c.set( "a b", "c d" );
-  std::string s;
-  EXPECT_TRUE( c.get( "a b", &s ));
-  EXPECT_EQ( "c d", s );
-
-  std::stringstream ss;
-  c.write( ss );
-  EXPECT_EQ( "a\\ b=c d\n", ss.str() );
-}
-
-TEST( Config, escape_colon )
-{
-  rviz::Config c;
-  c.set( "a:b", "c:d" );
-  std::string s;
-  EXPECT_TRUE( c.get( "a:b", &s ));
-  EXPECT_EQ( "c:d", s );
-
-  std::stringstream ss;
-  c.write( ss );
-  EXPECT_EQ( "a\\:b=c:d\n", ss.str() );
-}
-
-TEST( Config, first_slash_is_optional )
-{
-  rviz::Config c;
-  c.set( "a", 1 );
-  int i;
-  EXPECT_TRUE( c.get( "/a", &i ));
-  EXPECT_EQ( 1, i );
-
-  c.set( "/b", 2 );
-  EXPECT_TRUE( c.get( "b", &i ));
-  EXPECT_EQ( 2, i );
-}
-
-TEST( Config, end_to_end )
-{
-  rviz::Config c;
-  c.set( "/a: b/foo/bar", 1.25f );
-  c.set( "/a: b/foo/biff", 17 );
-  c.set( "a", "a/b=c d" );
-
-  std::stringstream ss;
-  c.write( ss );
-
-  c.clear();
-
-  c.read( ss );
-  float f;
-  EXPECT_TRUE( c.get( "/a: b/foo/bar", &f ));
-  EXPECT_EQ( 1.25, f ); // I don't need approximately-equal because I chose a floating-point-friendly number.
-  int i;
-  EXPECT_TRUE( c.get( "/a: b/foo/biff", &i ));
-  EXPECT_EQ( 17, i );
-  std::string s;
-  EXPECT_TRUE( c.get( "a", &s ));
-  EXPECT_EQ( "a/b=c d", s );
-}
-
-TEST( Config, file_io )
-{
-  std::string package_path = ros::package::getPath(ROS_PACKAGE_NAME);
-
-  rviz::Config c;
-  EXPECT_TRUE( c.readFromFile( package_path + "/src/test/test_in.vcg" ));
-  EXPECT_TRUE( c.writeToFile( package_path + "/build/test_out.vcg" ));
-
-  // This test would be better if it sorted the input and output files
-  // and checked that the results were the same.  I don't care enough
-  // to learn how to do that with gtest right now.
-}
-
 int main(int argc, char **argv){
   testing::InitGoogleTest(&argc, argv);
   return RUN_ALL_TESTS();
diff --git a/src/test/display_test.cpp b/src/test/display_test.cpp
index 1e83730..f9cfde1 100644
--- a/src/test/display_test.cpp
+++ b/src/test/display_test.cpp
@@ -29,15 +29,18 @@
 
 #include <gtest/gtest.h>
 
-#include <ros/ros.h>
+#include <QApplication>
 
-#include <yaml-cpp/yaml.h>
+#include <ros/ros.h>
 
 #include <sstream>
 
 #include <rviz/properties/vector_property.h>
 #include <rviz/properties/color_property.h>
 #include <rviz/display_group.h>
+#include <rviz/config.h>
+#include <rviz/yaml_config_reader.h>
+#include <rviz/yaml_config_writer.h>
 
 #include "mock_display.h"
 #include "mock_context.h"
@@ -54,12 +57,12 @@ TEST( Display, load_properties )
                            "Color: white\n"
                            "Style: loosey goosey\n" );
 
-  YAML::Parser parser( input );
-  YAML::Node node;
-  parser.GetNextDocument( node );
+  rviz::YamlConfigReader reader;
+  rviz::Config config;
+  reader.readStream(config, input);
 
   MockDisplay d;
-  d.load( node );
+  d.load( config );
 
   EXPECT_EQ( 7, d.count_->getValue().toInt() );
   EXPECT_EQ( "loosey goosey", d.style_->getValue().toString().toStdString() );
@@ -100,15 +103,12 @@ TEST( DisplayGroup, load_properties )
     "   Count: 33\n"
     );
 
-  YAML::Parser parser( input );
-  YAML::Node node;
-  parser.GetNextDocument( node );
-
-  MockContext context;
+  rviz::YamlConfigReader reader;
+  rviz::Config config;
+  reader.readStream(config, input);
 
   DisplayGroup g;
-  g.initialize( &context );
-  g.load( node );
+  g.load( config );
 
   EXPECT_EQ( true, g.getValue().toBool() );
   EXPECT_EQ( false, g.subProp("Steven")->getValue().toBool() );
@@ -124,12 +124,14 @@ TEST( Display, save_properties)
   d.setName( "Steven" );
   d.subProp( "Count" )->setValue( 37 );
 
-  YAML::Emitter out;
-  d.save( out );
+  rviz::YamlConfigWriter writer;
+  rviz::Config config;
+  d.save( config );
+  QString out = writer.writeString(config);
 
   // Since we instantiated the display directly instead of using the
   // DisplayFactory, it won't know its class name.
-  EXPECT_EQ( std::string( 
+  EXPECT_EQ( std::string(
                "Class: \"\"\n"
                "Name: Steven\n"
                "Enabled: false\n"
@@ -139,7 +141,7 @@ TEST( Display, save_properties)
                "Offset: {X: 1, Y: 2, Z: 3}\n"
                "Color: 10; 20; 30"
                )
-             , out.c_str() );
+             , out.toStdString().c_str() );
 }
 
 TEST( DisplayGroup, save_properties)
@@ -157,12 +159,14 @@ TEST( DisplayGroup, save_properties)
   d->subProp( "Pi" )->setValue( 1.1 );
   g.addChild( d );
 
-  YAML::Emitter out;
-  g.save( out );
+  rviz::YamlConfigWriter writer;
+  rviz::Config config;
+  g.save( config );
+  QString out = writer.writeString(config);
 
   // Since we instantiated the display directly instead of using the
   // DisplayFactory, it won't know its class name.
-  EXPECT_EQ( std::string( 
+  EXPECT_EQ( std::string(
                "Class: \"\"\n"
                "Name: Charles\n"
                "Enabled: false\n"
@@ -184,7 +188,7 @@ TEST( DisplayGroup, save_properties)
                "    Offset: {X: 1, Y: 2, Z: 3}\n"
                "    Color: 10; 20; 30"
                )
-             , out.c_str() );
+             , out.toStdString().c_str() );
 }
 
 TEST( DisplayFactory, class_name )
@@ -195,15 +199,12 @@ TEST( DisplayFactory, class_name )
     "   Class: MockDisplay\n"
     );
 
-  YAML::Parser parser( input );
-  YAML::Node node;
-  parser.GetNextDocument( node );
-
-  MockContext context;
+  rviz::YamlConfigReader reader;
+  rviz::Config config;
+  reader.readStream(config, input);
 
   DisplayGroup g;
-  g.initialize( &context );
-  g.load( node );
+  g.load( config );
 
   EXPECT_EQ( 1, g.numChildren() );
   EXPECT_EQ( "MockDisplay", g.getDisplayAt( 0 )->getClassId().toStdString() );
@@ -223,15 +224,12 @@ TEST( DisplayFactory, failed_display )
     "        food: bard\n"
     );
 
-  YAML::Parser parser( input );
-  YAML::Node node;
-  parser.GetNextDocument( node );
-
-  MockContext context;
+  rviz::YamlConfigReader reader;
+  rviz::Config config;
+  reader.readStream(config, input);
 
   DisplayGroup g;
-  g.initialize( &context );
-  g.load( node );
+  g.load( config );
 
   EXPECT_EQ( 1, g.numChildren() );
   EXPECT_EQ( "MissingDisplay", g.getDisplayAt( 0 )->getClassId().toStdString() );
@@ -239,8 +237,10 @@ TEST( DisplayFactory, failed_display )
 
   // When a FailedDisplay is saved, it should write out its contents
   // that it was loaded with, so data is not lost.
-  YAML::Emitter out;
-  g.save( out );
+  rviz::YamlConfigWriter writer;
+  rviz::Config config2;
+  g.save( config2 );
+  QString out = writer.writeString(config);
   EXPECT_EQ( std::string(
                "Class: \"\"\n"
                "Name: \"\"\n"
@@ -255,11 +255,12 @@ TEST( DisplayFactory, failed_display )
                "      - foo: bar\n"
                "        food: bard"
                )
-             , out.c_str() );
+             , out.toStdString().c_str() );
 }
 
 int main( int argc, char **argv ) {
-  ros::init( argc, argv, "test", ros::init_options::AnonymousName );
+  ros::init( argc, argv, "display_test", ros::init_options::AnonymousName );
+  QApplication app(argc, argv);
   testing::InitGoogleTest( &argc, argv );
   return RUN_ALL_TESTS();
 }
diff --git a/src/test/display_test.test b/src/test/display_test.test
new file mode 100644
index 0000000..1f99871
--- /dev/null
+++ b/src/test/display_test.test
@@ -0,0 +1,3 @@
+<launch>
+  <test pkg="rviz" type="display_test" name="display_test" test-name="display_test" time-limit="2.0" />
+</launch>
diff --git a/src/test/fun_display.cpp b/src/test/fun_display.cpp
deleted file mode 100644
index bebb061..0000000
--- a/src/test/fun_display.cpp
+++ /dev/null
@@ -1,137 +0,0 @@
-/*
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include <stdlib.h> // for random
-#include <stdio.h> // for printf
-
-#include <QTimer>
-
-#include "fun_display.h"
-
-// static member
-FunDisplay* FunDisplay::previous_fun_ = NULL;
-
-FunDisplay::FunDisplay()
-  : count_( 0 )
-{
-  size_ = new Property( "Size", 10, "How big, in units", this );
-  connect( size_, SIGNAL( changed() ), this, SLOT( onSizeChanged() ));
-
-  master_ = new Property( "Master", "chunky", "Type of butter.", this );
-  connect( master_, SIGNAL( changed() ), this, SLOT( onMasterChanged() ));
-
-  if( previous_fun_ )
-  {
-    connect( previous_fun_->master_, SIGNAL( changed() ), this, SLOT( onMasterChanged() ));
-  }
-  previous_fun_ = this;
-
-  new Property( "Double", 1.0, "double", this );
-  new Property( "Float", 1.0f, "float", this );
-
-  slave_ = new Property( "Slave", "chunky", "Slave to the butter.", this );
-
-  mood_ = new EnumProperty( "Mood", "sad", "Feelings, nothing more than feelings...", this );
-  mood_->addOption( "sad", 0 );
-  mood_->addOption( "happy", 1 );
-  mood_->addOption( "angry", 2 );
-  mood_->addOption( "jumpy", 3 );
-  mood_->addOption( "squirmy", 4 );
-  connect( mood_, SIGNAL( changed() ), this, SLOT( onMoodChanged() ));
-
-  dance_ = new EditableEnumProperty( "Dance", "clown", "Stomple stomple", this );
-  connect( dance_, SIGNAL( requestOptions( EditableEnumProperty* )), this, SLOT( makeDances( EditableEnumProperty* )));
-
-  QTimer* timer = new QTimer( this );
-  connect( timer, SIGNAL( timeout() ), this, SLOT( onTimerTick() ));
-  timer->start( 1000 );
-}
-
-void FunDisplay::onTimerTick()
-{
-  count_++;
-  slave_->setValue( count_ );
-  if( (count_ / 10) % 2 )
-  {
-    setStatus( StatusProperty::Warn, "Slave", "Too odd." );
-  }
-  else
-  {
-    setStatus( StatusProperty::Ok, "Slave", "Even enough." );
-  }
-}
-
-void FunDisplay::onMasterChanged()
-{
-  slave_->setValue( master_->getValue() );
-}
-
-void FunDisplay::onSizeChanged()
-{
-  if( size_->getValue().toInt() > 10 )
-  {
-    setStatus( StatusProperty::Error, "Size", "Too large." );
-  }
-  else if( size_->getValue().toInt() < 5 )
-  {
-    setStatus( StatusProperty::Warn, "Size", "Too small." );
-  }
-  else
-  {
-    setStatus( StatusProperty::Ok, "Size", "Just fine." );
-  }
-}
-
-void FunDisplay::onMoodChanged()
-{
-  printf( "Mood is now %d.\n", mood_->getOptionInt() );
-}
-
-void FunDisplay::makeDances( EditableEnumProperty* prop )
-{
-  QStringList dances;
-  dances.push_back( "Robot/Turtlebot" );
-  dances.push_back( "Robot/PR2" );
-  dances.push_back( "Macarena/Fast" );
-  dances.push_back( "Macarena/Slow" );
-  dances.push_back( "Twist" );
-  dances.push_back( "Tango" );
-  dances.push_back( "Swing/Lindy" );
-  dances.push_back( "Swing/Hop/Small" );
-  dances.push_back( "Swing/Hop/Big" );
-  dances.push_back( "Stumble" );
-  dances.push_back( "Stomple" );
-
-  prop->clearOptions();
-  for( int i = 0; i < 9; i++ )
-  {
-    int index = random() % dances.size();
-    prop->addOption( dances[ index ]);
-  }
-}
diff --git a/src/test/image_test.cpp b/src/test/image_test.cpp
index 1604fad..bf0fe3f 100644
--- a/src/test/image_test.cpp
+++ b/src/test/image_test.cpp
@@ -4,7 +4,7 @@
 
 int main( int argc, char** argv )
 {
-  ros::init( argc, argv, "cloud_test" );
+  ros::init( argc, argv, "image_test" );
 
   ros::NodeHandle n;
 
diff --git a/src/test/meshes/ascii.stl b/src/test/meshes/ascii.stl
new file mode 100644
index 0000000..91e1721
--- /dev/null
+++ b/src/test/meshes/ascii.stl
@@ -0,0 +1,19 @@
+solid ascii.stl
+
+facet normal 0.648000e-001 0.648000e-002 0.648000e-003
+  outer loop
+    vertex 1.648000e-001 2.648000e-002 3.648000e-003
+    vertex 4.648000e-001 5.648000e-002 6.648000e-003
+    vertex 7.648000e-001 8.648000e-002 9.648000e-003
+  end loop
+end facet
+
+facet normal 4.648000e-001 4.648000e-002 4.648000e-003
+  outer loop
+    vertex 10.648000e-001 11.648000e-002 12.648000e-003
+    vertex 13.648000e-001 14.648000e-002 15.648000e-003
+    vertex 16.648000e-001 17.648000e-002 18.648000e-003
+  end loop
+end facet
+
+endsolid ascii.stl
diff --git a/src/test/meshes/invalid.stl b/src/test/meshes/invalid.stl
new file mode 100644
index 0000000..7c5cb1f
Binary files /dev/null and b/src/test/meshes/invalid.stl differ
diff --git a/src/test/meshes/invalid_short.stl b/src/test/meshes/invalid_short.stl
new file mode 100644
index 0000000..4ae56bc
Binary files /dev/null and b/src/test/meshes/invalid_short.stl differ
diff --git a/src/test/meshes/valid.stl b/src/test/meshes/valid.stl
new file mode 100644
index 0000000..1d5df33
Binary files /dev/null and b/src/test/meshes/valid.stl differ
diff --git a/src/test/mock_context.h b/src/test/mock_context.h
index 110d49d..ac1efbf 100644
--- a/src/test/mock_context.h
+++ b/src/test/mock_context.h
@@ -44,20 +44,22 @@ public:
   virtual SelectionManager* getSelectionManager() const { return 0; }
   virtual FrameManager* getFrameManager() const { return 0; }
   virtual tf::TransformListener* getTFClient() const { return 0; }
-  virtual void queueRender() {}
   virtual QString getFixedFrame() const { return ""; }
   virtual uint64_t getFrameCount() const { return 0; }
   virtual DisplayFactory* getDisplayFactory() const { return display_factory_; }
   virtual ros::CallbackQueueInterface* getUpdateQueue() { return 0; }
   virtual ros::CallbackQueueInterface* getThreadedQueue() { return 0; }
-  virtual void handleChar( QKeyEvent* event, RenderPanel* panel ) {};
-  virtual void handleMouseEvent( const ViewportMouseEvent& event ) {};
+  virtual void handleChar( QKeyEvent* event, RenderPanel* panel ) {}
+  virtual void handleMouseEvent( const ViewportMouseEvent& event ) {}
   virtual ToolManager* getToolManager() const { return 0; }
   virtual ViewManager* getViewManager() const { return 0; }
-  virtual RenderPanel* getRenderPanel() const { return 0; }
   virtual DisplayGroup* getRootDisplayGroup() const { return 0; }
   virtual uint32_t getDefaultVisibilityBit() const { return 0; }
   virtual BitAllocator* visibilityBits() { return 0; }
+  virtual void setStatus( const QString & message ) {}
+
+  virtual void queueRender() {}
+
 private:
   DisplayFactory* display_factory_;
 };
diff --git a/src/test/new_display_dialog_test.cpp b/src/test/new_display_dialog_test.cpp
index ec331ce..5c764ab 100644
--- a/src/test/new_display_dialog_test.cpp
+++ b/src/test/new_display_dialog_test.cpp
@@ -31,22 +31,35 @@
 
 #include <QApplication>
 
+#include <pluginlib/class_loader.h>
+
+#include "rviz/display.h"
+#include "rviz/pluginlib_factory.h"
 #include "rviz/new_object_dialog.h"
 
 int main( int argc, char **argv )
 {
   QApplication app( argc, argv );
 
-  std::string lookup_name;
-  std::string display_name;
-  pluginlib::ClassLoader<rviz::Display>* class_loader = new pluginlib::ClassLoader<rviz::Display>( "rviz", "rviz::Display" );
-  rviz::S_string current_names;
-  current_names.insert( "Chub" );
-  current_names.insert( "Town" );
-  rviz::NewObjectDialog* dialog = new rviz::NewObjectDialog( class_loader, "Display", current_names, &lookup_name, &display_name );
+  QString lookup_name;
+  QString display_name;
+  rviz::PluginlibFactory<rviz::Display> * factory = new rviz::PluginlibFactory<rviz::Display>( "rviz", "rviz::Display" );
+  typedef std::set<std::pair<uint8_t, std::string> > S_string;
+  QStringList current_names;
+  current_names << "Chub" << "Town";
+  QStringList empty;
+  rviz::NewObjectDialog* dialog = new rviz::NewObjectDialog(
+    factory,
+    QString("Display"),
+    current_names,
+    empty,
+    &lookup_name,
+    &display_name,
+    0
+  );
   if( dialog->exec() == QDialog::Accepted )
   {
-    printf( "lookup_name='%s', display_name='%s'\n", lookup_name.c_str(), display_name.c_str() );
+    printf( "lookup_name='%s', display_name='%s'\n", lookup_name.toStdString().c_str(), display_name.toStdString().c_str() );
   }
   else
   {
diff --git a/src/test/other-help.html b/src/test/other-help.html
deleted file mode 100644
index 60eeff3..0000000
--- a/src/test/other-help.html
+++ /dev/null
@@ -1,12 +0,0 @@
-<!--
-   Please note: This HTML file is displayed by a QTextBrowser widget
-   in rviz.  QTextBrowser supports only a SUBSET of HTML.
-
-   See http://developer.qt.nokia.com/doc/qt-4.8/richtext-html-subset.html
-   for the details.
--->
-<html>
-<body>
-<h3>Custom help file</h3>
-</body>
-</html>
diff --git a/src/test/playground.cpp b/src/test/playground.cpp
deleted file mode 100644
index a41dd05..0000000
--- a/src/test/playground.cpp
+++ /dev/null
@@ -1,206 +0,0 @@
-/*
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include <QApplication>
-#include <QPushButton>
-#include <QVBoxLayout>
-#include <QFileDialog>
-
-#include <fstream>
-#include <sstream>
-
-#include <yaml-cpp/yaml.h>
-
-#include "rviz/properties/color_property.h"
-#include "rviz/properties/property.h"
-#include "rviz/properties/quaternion_property.h"
-#include "rviz/properties/vector_property.h"
-#include "rviz/properties/property_tree_model.h"
-#include "rviz/properties/property_tree_widget.h"
-#include "rviz/properties/status_list.h"
-#include "rviz/display.h"
-#include "rviz/display_group.h"
-#include "rviz/visualization_manager.h"
-
-#include "fun_display.h"
-#include "mock_display_factory.h"
-
-#include "playground.h"
-
-void makeBigTree( DisplayGroup* parent )
-{
-  Display* disp;
-  for( int i = 0; i < 100; i++ )
-  {
-    disp = new FunDisplay();
-    disp->setName( "D" + QString::number( i ));
-    disp->setParentProperty( parent );
-
-    for( int j = 0; j < 100; j++ )
-    {
-      new Property( "prop" + QString::number( j ), j, "how many", disp );
-    }
-  }
-}
-
-Playground::Playground( QWidget* parent )
-  : QWidget( parent )
-{
-  factory_ = new MockDisplayFactory;
-  vis_man_ = new VisualizationManager;
-  vis_man_->setDisplayFactory( factory_ );
-
-  root_ = new DisplayGroup;
-  model_ = new PropertyTreeModel( root_ );
-/*
-  std::stringstream input(
-    "Enabled: true\n"
-    "Displays:\n"
-    " -\n"
-    "   Class: MockDisplay\n"
-    "   Name: Steven\n"
-    "   Enabled: false\n"
-    "   Count: 17\n"
-    " -\n"
-    "   Name: sub group\n"
-    "   Class: DisplayGroup\n"
-    "   Enabled: true\n"
-    "   Displays:\n"
-    "    -\n"
-    "      Class: MockDisplay\n"
-    "      Name: Curly\n"
-    "      Enabled: false\n"
-    "      Count: 900\n"
-    " -\n"
-    "   Class: BrokenDisplay\n"
-    "   Name: Joe\n"
-    "   Enabled: true\n"
-    "   Count: 33\n"
-    );
-
-  YAML::Parser parser( input );
-  YAML::Node node;
-  parser.GetNextDocument( node );
-
-  root_->initialize( vis_man_ );
-  root_->load( node );
-*/
-
-  Display* display = new Display();
-  display->setName( "Test" );
-  display->setParentProperty( root_ );
-  new Property( "Alpha", 0.5, "The amount of transparency to apply to the grid lines.", display );
-  new Property( "Beta Band", 10, "The number of betas to apply to the grid lines.", display );
-  new Property( "Gamma Topic", "chubby", "The topic on which to listen for Gamma messages.", display );
-  Property* position = new Property( "Position", QVariant(), "Position of the chub.", display );
-  new Property( "X", 1.1, "X component of the position of the chub.", position );
-  new Property( "Y", 0.717, "Y component of the position of the chub.", position );
-  DisplayGroup* group = new DisplayGroup();
-  group->setName( "Group" );
-  group->setParentProperty( root_ );
-  DisplayGroup* sub_group = new DisplayGroup();
-  sub_group->setName( "SubGroup" );
-  sub_group->setParentProperty( group );
-  Display* display2 = new Display();
-  display2->setName( "Taste" );
-  display2->setParentProperty( group );
-  DisplayGroup* cruft = new DisplayGroup();
-  cruft->setName( "Cruft" );
-  cruft->setParentProperty( root_ );
-  new VectorProperty( "Vector", Ogre::Vector3( 1, 2, 3 ), "3 numbers in a row.", display2 );
-  new QuaternionProperty( "Quaternion", Ogre::Quaternion( 1, 0, 0, 0 ), "4 numbers in a row!", display2 );
-  Display* display3 = new Display();
-  display3->setName( "Toast" );
-  display3->setParentProperty( group );
-  new ColorProperty( "Color", QColor( 1, 2, 3 ), "Better than black and white.", display3 );
-  Display* display4 = new Display();
-  display4->setName( "Lamby" );
-  display4->setParentProperty( group );
-  StatusList* stat = new StatusList( display4 );
-  stat->setStatus( StatusProperty::Warn, "Topic", "No messages received." );
-  stat->setStatus( StatusProperty::Error, "Size", "Size is too large." );
-  stat->setStatus( StatusProperty::Ok, "Cheese", "Cheese is tasty." );
-  stat = new StatusList( display );
-  stat->setStatus( StatusProperty::Warn, "Topic", "No messages received." );
-  stat->setStatus( StatusProperty::Error, "Size", "Size is too large." );
-  stat->setStatus( StatusProperty::Ok, "Cheese", "Cheese is tasty." );
-
-  FunDisplay* fun = new FunDisplay();
-  fun->setName( "Fun" );
-  fun->setParentProperty( group );
-
-  fun = new FunDisplay();
-  fun->setName( "Funner" );
-  fun->setParentProperty( group );
-
-  PropertyTreeWidget* w = new PropertyTreeWidget;
-  w->setModel( model_ );
-
-//  makeBigTree( cruft );
-
-  QPushButton* load_button = new QPushButton( "load" );
-  connect( load_button, SIGNAL( clicked() ), this, SLOT( openLoadFileDialog() ));
-
-  QVBoxLayout* main_layout = new QVBoxLayout;
-  main_layout->addWidget( w );
-  main_layout->addWidget( load_button );
-
-  setLayout( main_layout );
-
-  setWindowTitle("fun");
-}
-
-void Playground::openLoadFileDialog()
-{
-  QString filename = QFileDialog::getOpenFileName( this );
-  std::ifstream in( filename.toStdString().c_str() );
-  if( in )
-  {
-    YAML::Parser parser( in );
-    YAML::Node node;
-    parser.GetNextDocument( node );
-    root_->initialize( vis_man_ );
-    root_->load( node );
-  }
-  else
-  {
-    printf("Failed to read file %s.\n", qPrintable( filename ));
-  }
-}
-
-int main( int argc, char **argv )
-{
-  QApplication app( argc, argv );
-
-  Playground w;
-  w.resize( 400, 600 );
-  w.show();
-
-  return app.exec();
-}
diff --git a/src/test/playground.h b/src/test/playground.h
deleted file mode 100644
index 53aca39..0000000
--- a/src/test/playground.h
+++ /dev/null
@@ -1,54 +0,0 @@
-/*
- * Copyright (c) 2012, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-#ifndef PLAYGROUND_H
-#define PLAYGROUND_H
-
-#include <QWidget>
-
-class DisplayGroup;
-class PropertyTreeModel;
-class MockDisplayFactory;
-class VisualizationManager;
-
-class Playground: public QWidget
-{
-Q_OBJECT
-public:
-  Playground( QWidget* parent = 0 );
-
-  DisplayGroup* root_;
-  PropertyTreeModel* model_;
-  MockDisplayFactory* factory_;
-  VisualizationManager* vis_man_;
-
-public Q_SLOTS:
-  void openLoadFileDialog();
-};
-
-#endif // PLAYGROUND_H
diff --git a/src/test/render_panel_test.cpp b/src/test/render_panel_test.cpp
index e62985f..6618b9e 100644
--- a/src/test/render_panel_test.cpp
+++ b/src/test/render_panel_test.cpp
@@ -34,7 +34,6 @@
 #include "rviz/visualization_manager.h"
 #include "rviz/render_panel.h"
 #include "rviz/displays_panel.h"
-#include "rviz/properties/property_manager.h"
 
 using namespace rviz;
 
@@ -49,7 +48,7 @@ int main(int argc, char **argv)
 
   render_panel->initialize( vman->getSceneManager(), vman );
   displays_panel->initialize( vman );
-  vman->initialize( StatusCallback(), false );
+  vman->initialize();
   vman->startUpdate();
 
   render_panel->show();
diff --git a/src/test/render_points_test.cpp b/src/test/render_points_test.cpp
index 38fea3d..424f644 100644
--- a/src/test/render_points_test.cpp
+++ b/src/test/render_points_test.cpp
@@ -142,9 +142,9 @@ MyFrame::MyFrame( QWidget* parent )
         {
           //    int32_t index = (ycount*zcount*x) + zcount*y + z;
           PointCloud::Point point;// = points[index];
-          point.x = x * factor;
-          point.y = y * factor;
-          point.z = z * factor;
+          point.position.x = x * factor;
+          point.position.y = y * factor;
+          point.position.z = z * factor;
 
           point.setColor(x * 0.1, y * 0.1, z * 0.1);
           points.push_back(point);
diff --git a/src/test/render_points_test.h b/src/test/render_points_test.h
index b14e13a..f56cc5d 100644
--- a/src/test/render_points_test.h
+++ b/src/test/render_points_test.h
@@ -33,6 +33,7 @@
 #include <QWidget>
 #include <QTimer>
 
+#ifndef Q_MOC_RUN  // See: https://bugreports.qt-project.org/browse/QTBUG-22829
 #include "rviz/ogre_helpers/qt_ogre_render_window.h"
 #include "rviz/ogre_helpers/grid.h"
 #include "rviz/ogre_helpers/orbit_camera.h"
@@ -49,6 +50,7 @@
 #include <OgreLight.h>
 
 #include <ros/time.h>
+#endif
 
 using namespace rviz;
 
diff --git a/src/test/ros_spinner.h b/src/test/ros_spinner.h
index 9ba5281..5f2c544 100644
--- a/src/test/ros_spinner.h
+++ b/src/test/ros_spinner.h
@@ -32,7 +32,9 @@
 
 #include <QObject>
 
-#include <ros/ros.h>
+#ifndef Q_MOC_RUN  // See: https://bugreports.qt-project.org/browse/QTBUG-22829
+# include <ros/ros.h>
+#endif
 
 class RosSpinner: public QObject
 {
diff --git a/src/test/rviz_logo_marker.cpp b/src/test/rviz_logo_marker.cpp
index d707b1e..8abfb48 100644
--- a/src/test/rviz_logo_marker.cpp
+++ b/src/test/rviz_logo_marker.cpp
@@ -4,8 +4,8 @@
 #include "visualization_msgs/MarkerArray.h"
 #include "interactive_markers/interactive_marker_server.h"
 
-#include <tf/transform_broadcaster.h>
 #include <tf/tf.h>
+#include <tf/transform_broadcaster.h>
 
 interactive_markers::InteractiveMarkerServer* server;
 
@@ -26,7 +26,7 @@ void makeMarker( )
   visualization_msgs::Marker marker;
   marker.type = visualization_msgs::Marker::MESH_RESOURCE;
 
-  tf::quaternionTFToMsg( btQuaternion( btVector3(0,0,1), 0.2 ), marker.pose.orientation );
+  tf::quaternionTFToMsg( tf::Quaternion( tf::Vector3(0, 0, 1), 0.2 ), marker.pose.orientation );
 
   marker.pose.position.x = 0;
   marker.pose.position.y = -0.22;
@@ -85,7 +85,7 @@ void publishCallback(tf::TransformBroadcaster& tf_broadcaster, const ros::TimerE
   static tf::TransformBroadcaster br;
   tf::Transform transform;
   transform.setOrigin( tf::Vector3(3, 1, 0) );
-  transform.setRotation( tf::Quaternion(0, 0, M_PI*0.9) );
+  transform.setRotation( tf::createQuaternionFromRPY(0, 0, M_PI * 0.9) );
   br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "base_link", "rviz_logo"));
 }
 
diff --git a/src/test/stl_loader_test.cpp b/src/test/stl_loader_test.cpp
new file mode 100644
index 0000000..739ea68
--- /dev/null
+++ b/src/test/stl_loader_test.cpp
@@ -0,0 +1,33 @@
+#include <gtest/gtest.h>
+#include <boost/filesystem.hpp>
+#include <ros/package.h>
+#include <rviz/ogre_helpers/stl_loader.h>
+
+TEST( STLLoader, load )
+{
+  // Get the path to the directory where the meshes are located.
+  boost::filesystem::path meshDir = ros::package::getPath("rviz");
+  meshDir /= "src/test/meshes";
+
+  // Load an ascii STL file. Note that only binary STL files are supported.
+  ogre_tools::STLLoader loader;
+  boost::filesystem::path meshFilePath = meshDir / "ascii.stl";
+  EXPECT_FALSE(loader.load(meshFilePath.string()));
+
+  // Load an invalid STL binary file (size < 84 bytes).
+  meshFilePath = meshDir / "invalid_short.stl";
+  EXPECT_FALSE(loader.load(meshFilePath.string()));
+
+  // Load an invalid STL binary file (size does not match the expected size).
+  meshFilePath = meshDir / "invalid.stl";
+  EXPECT_FALSE(loader.load(meshFilePath.string()));
+
+  // Load a valid STL binary file.
+  meshFilePath = meshDir / "valid.stl";
+  EXPECT_TRUE(loader.load(meshFilePath.string()));
+}
+
+int main( int argc, char **argv ) {
+  testing::InitGoogleTest( &argc, argv );
+  return RUN_ALL_TESTS();
+}
diff --git a/src/test/topic_dialog_test.cpp b/src/test/topic_dialog_test.cpp
deleted file mode 100644
index b0f87e3..0000000
--- a/src/test/topic_dialog_test.cpp
+++ /dev/null
@@ -1,58 +0,0 @@
-/*
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "rviz/properties/ros_topic_dialog.h"
-
-#include "ros/ros.h"
-
-#include <QtGui/QApplication>
-
-#include <stdio.h>
-
-using namespace rviz;
-
-int main(int argc, char **argv)
-{
-  ros::init( argc, argv, "topic_dialog_test" );
-
-  QApplication app(argc, argv);
-
-  std::string topic_name;
-  RosTopicDialog* rtd = new RosTopicDialog( "std_msgs/String", &topic_name );
-  if( rtd->exec() == QDialog::Accepted )
-  {
-    printf( "topic chosen: '%s'\n", topic_name.c_str() );
-  }
-  else
-  {
-    printf( "cancel!\n" );
-  }
-
-  return 0;
-}
diff --git a/src/test/topic_info_variant_test.cpp b/src/test/topic_info_variant_test.cpp
deleted file mode 100644
index 77c293c..0000000
--- a/src/test/topic_info_variant_test.cpp
+++ /dev/null
@@ -1,70 +0,0 @@
-/*
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-#include <gtest/gtest.h>
-
-#include <QVariant>
-
-#include "rviz/properties/topic_info_variant.h"
-
-TEST( RosTopicVar, basic )
-{
-  ros::master::TopicInfo rtv;
-  rtv.datatype = "std_msgs/String";
-  rtv.name = "/ns/chatter";
-
-  QVariant var = 7;
-  EXPECT_EQ( var.type(), QVariant::Int );
-  EXPECT_FALSE( var.canConvert<ros::master::TopicInfo>() );
-  
-  var = QVariant::fromValue( rtv );
-
-// For some reason these are not equal!  Looks like QVariant has a
-// different idea about typeIds than qMetaTypeId does.  Result: don't
-// use qMetaTypeId<>() to identify QVariant types, just use
-// QVariant::canConvert<>().
-//
-//  EXPECT_EQ( var.type(), qMetaTypeId<ros::master::TopicInfo>() );
-
-  EXPECT_TRUE( var.canConvert<ros::master::TopicInfo>() );
-
-  QVariant var2 = var;
-
-  ros::master::TopicInfo rtv2 = var.value<ros::master::TopicInfo>();
-  EXPECT_EQ( "std_msgs/String", rtv2.datatype );
-  EXPECT_EQ( "/ns/chatter", rtv2.name );
-
-  ros::master::TopicInfo rtv3 = var2.value<ros::master::TopicInfo>();
-  EXPECT_EQ( "std_msgs/String", rtv3.datatype );
-  EXPECT_EQ( "/ns/chatter", rtv3.name );
-}
-
-int main(int argc, char **argv){
-  testing::InitGoogleTest(&argc, argv);
-  return RUN_ALL_TESTS();
-}
diff --git a/src/test/vis_panel_example.cpp b/src/test/vis_panel_example.cpp
deleted file mode 100644
index d9188f3..0000000
--- a/src/test/vis_panel_example.cpp
+++ /dev/null
@@ -1,63 +0,0 @@
-/*
- * Copyright (c) 2011, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- *     * Redistributions of source code must retain the above copyright
- *       notice, this list of conditions and the following disclaimer.
- *     * Redistributions in binary form must reproduce the above copyright
- *       notice, this list of conditions and the following disclaimer in the
- *       documentation and/or other materials provided with the distribution.
- *     * Neither the name of the Willow Garage, Inc. nor the names of its
- *       contributors may be used to endorse or promote products derived from
- *       this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include <QApplication>
-#include <QPushButton>
-#include <QVBoxLayout>
-#include <QHBoxLayout>
-
-#include "rviz/visualization_panel.h"
-
-using namespace rviz;
-
-int main(int argc, char **argv)
-{
-  QApplication app( argc, argv );
-
-  QPushButton* accept = new QPushButton( "Accept" );
-  QPushButton* reject = new QPushButton( "Reject" );
-
-  QVBoxLayout* button_layout = new QVBoxLayout;
-  button_layout->addWidget( accept );
-  button_layout->addWidget( reject );
-
-  VisualizationPanel* frame = new VisualizationPanel;
-
-  QHBoxLayout* main_layout = new QHBoxLayout;
-  main_layout->addLayout( button_layout );
-  main_layout->addWidget( frame );
-
-  QWidget* main_window = new QWidget;
-  main_window->setLayout( main_layout );
-  main_window->show();
-
-  app.exec();
-
-  delete main_window;
-}

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/ros/rviz.git



More information about the debian-science-commits mailing list