Skip to content

Commit

Permalink
Added #ifdef Q_MOC_RUN all over to fix quantal build.
Browse files Browse the repository at this point in the history
Newer version of Boost library used in quantal includes c++ syntax which Qt's 'moc' does not understand.
  • Loading branch information
hershwg committed Nov 14, 2012
1 parent 5dc295e commit 00983d9
Show file tree
Hide file tree
Showing 10 changed files with 20 additions and 4 deletions.
2 changes: 2 additions & 0 deletions src/rviz/default_plugin/camera_display.h
Expand Up @@ -37,8 +37,10 @@

#include <sensor_msgs/CameraInfo.h>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#endif

#include "rviz/image/image_display_base.h"
#include "rviz/image/ros_image_texture.h"
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/default_plugin/depth_cloud_display.h
Expand Up @@ -36,10 +36,12 @@
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <image_transport/subscriber_filter.h>
#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf/message_filter.h>
#endif

#include "rviz/properties/enum_property.h"
#include "rviz/properties/float_property.h"
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/default_plugin/grid_cells_display.h
Expand Up @@ -36,8 +36,10 @@
#include <nav_msgs/GridCells.h>
#include <nav_msgs/MapMetaData.h>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#endif

#include <boost/shared_ptr.hpp>

Expand Down
4 changes: 3 additions & 1 deletion src/rviz/default_plugin/interactive_marker_display.h
Expand Up @@ -37,13 +37,15 @@
#include <visualization_msgs/InteractiveMarkerUpdate.h>
#include <visualization_msgs/InteractiveMarkerInit.h>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#include <interactive_markers/interactive_marker_client.h>
#endif

#include "rviz/display.h"
#include "rviz/selection/forwards.h"

#include <interactive_markers/interactive_marker_client.h>
#include "rviz/default_plugin/interactive_markers/interactive_marker.h"

namespace rviz
Expand Down
3 changes: 2 additions & 1 deletion src/rviz/default_plugin/marker_display.h
Expand Up @@ -36,9 +36,10 @@
#include <boost/thread/mutex.hpp>
#include <boost/shared_ptr.hpp>

#ifndef Q_MOC_RUN
#include <tf/message_filter.h>

#include <message_filters/subscriber.h>
#endif

#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
Expand Down
3 changes: 3 additions & 0 deletions src/rviz/default_plugin/odometry_display.h
Expand Up @@ -36,8 +36,11 @@
#include <boost/shared_ptr.hpp>
#include <boost/thread/mutex.hpp>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#endif

#include <nav_msgs/Odometry.h>

#include "rviz/display.h"
Expand Down
2 changes: 0 additions & 2 deletions src/rviz/default_plugin/pose_display.h
Expand Up @@ -33,8 +33,6 @@

#include <boost/shared_ptr.hpp>

#include <message_filters/subscriber.h>

#include <geometry_msgs/PoseStamped.h>

#include "rviz/message_filter_display.h"
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/frame_manager.h
Expand Up @@ -43,7 +43,9 @@

#include <geometry_msgs/Pose.h>

#ifndef Q_MOC_RUN
#include <tf/message_filter.h>
#endif

namespace tf
{
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/image/image_display_base.h
Expand Up @@ -31,8 +31,10 @@

#include <QObject>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#endif
#include <sensor_msgs/Image.h>

#include <image_transport/image_transport.h>
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/message_filter_display.h
Expand Up @@ -32,8 +32,10 @@
#include <OGRE/OgreSceneManager.h>
#include <OGRE/OgreSceneNode.h>

#ifndef Q_MOC_RUN
#include <message_filters/subscriber.h>
#include <tf/message_filter.h>
#endif

#include "rviz/display_context.h"
#include "rviz/frame_manager.h"
Expand Down

0 comments on commit 00983d9

Please sign in to comment.