interactive_marker_display.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef RVIZ_INTERACTIVE_MARKER_DISPLAY_H
00031 #define RVIZ_INTERACTIVE_MARKER_DISPLAY_H
00032 
00033 #include <map>
00034 #include <set>
00035 
00036 #include <visualization_msgs/InteractiveMarker.h>
00037 #include <visualization_msgs/InteractiveMarkerUpdate.h>
00038 #include <visualization_msgs/InteractiveMarkerInit.h>
00039 
00040 #ifndef Q_MOC_RUN
00041 #include <message_filters/subscriber.h>
00042 #include <tf/message_filter.h>
00043 #include <interactive_markers/interactive_marker_client.h>
00044 #endif
00045 
00046 #include "rviz/display.h"
00047 #include "rviz/selection/forwards.h"
00048 
00049 #include "rviz/default_plugin/interactive_markers/interactive_marker.h"
00050 
00051 namespace rviz
00052 {
00053 class BoolProperty;
00054 class Object;
00055 class RosTopicProperty;
00056 class MarkerBase;
00057 
00058 typedef boost::shared_ptr<MarkerBase> MarkerBasePtr;
00059 typedef std::pair<std::string, int32_t> MarkerID;
00060 
00065 class InteractiveMarkerDisplay : public Display
00066 {
00067 Q_OBJECT
00068 public:
00069   InteractiveMarkerDisplay();
00070 
00071   virtual void onInitialize();
00072 
00073   virtual void update(float wall_dt, float ros_dt);
00074 
00075   virtual void fixedFrameChanged();
00076 
00077   virtual void reset();
00078   
00079 protected:
00080   virtual void onEnable();
00081   virtual void onDisable();
00082 
00083 protected Q_SLOTS:
00084   void updateTopic();
00085   void updateShowDescriptions();
00086   void updateShowAxes();
00087   void updateShowVisualAids();
00088   void updateEnableTransparency();
00089   void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00090   void onStatusUpdate( StatusProperty::Level level, const std::string& name, const std::string& text );
00091 
00092 private:
00093 
00094   // Subscribe to all message topics
00095   void subscribe();
00096 
00097   // Unsubscribe from all message topics
00098   void unsubscribe();
00099 
00100   void initCb( visualization_msgs::InteractiveMarkerInitConstPtr msg );
00101   void updateCb( visualization_msgs::InteractiveMarkerUpdateConstPtr msg );
00102 
00103   void resetCb( std::string server_id );
00104 
00105   void statusCb( interactive_markers::InteractiveMarkerClient::StatusT,
00106       const std::string& server_id,
00107       const std::string& msg );
00108 
00109   void updateMarkers(
00110       const std::string& server_id,
00111       const std::vector<visualization_msgs::InteractiveMarker>& markers );
00112 
00113   void updatePoses(
00114       const std::string& server_id,
00115       const std::vector<visualization_msgs::InteractiveMarkerPose>& marker_poses );
00116 
00117   void eraseMarkers(
00118       const std::string& server_id,
00119       const std::vector<std::string>& names );
00120 
00121   // Update the display's versions of the markers.
00122   void processMarkerChanges( const std::vector<visualization_msgs::InteractiveMarker>* markers = NULL,
00123                              const std::vector<visualization_msgs::InteractiveMarkerPose>* poses = NULL,
00124                              const std::vector<std::string>* erases = NULL );
00125 
00126   typedef boost::shared_ptr<InteractiveMarker> IMPtr;
00127   typedef std::map< std::string, IMPtr > M_StringToIMPtr;
00128   typedef std::map< std::string, M_StringToIMPtr > M_StringToStringToIMPtr;
00129   M_StringToStringToIMPtr interactive_markers_;
00130 
00131   M_StringToIMPtr& getImMap( std::string server_id );
00132 
00133   std::string client_id_;
00134 
00135   // Properties
00136   RosTopicProperty* marker_update_topic_property_;
00137   BoolProperty* show_descriptions_property_;
00138   BoolProperty* show_axes_property_;
00139   BoolProperty* show_visual_aids_property_;
00140   BoolProperty* enable_transparency_property_;
00141 
00142   boost::shared_ptr<interactive_markers::InteractiveMarkerClient> im_client_;
00143 
00144   ros::Publisher feedback_pub_;
00145 
00146   std::string topic_ns_;
00147 };
00148 
00149 } // namespace rviz
00150 
00151 #endif /* RVIZ_MARKER_DISPLAY_H */


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35