Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef RVIZ_INTERACTIVE_MARKER_DISPLAY_H
00031 #define RVIZ_INTERACTIVE_MARKER_DISPLAY_H
00032
00033 #include "rviz/default_plugin/interactive_markers/interactive_marker.h"
00034 #include "rviz/default_plugin/interactive_markers/interactive_marker_client.h"
00035
00036 #include "rviz/display.h"
00037 #include "rviz/selection/forwards.h"
00038 #include "rviz/properties/forwards.h"
00039
00040 #include <map>
00041 #include <set>
00042
00043 #include <visualization_msgs/InteractiveMarker.h>
00044 #include <visualization_msgs/InteractiveMarkerUpdate.h>
00045 #include <visualization_msgs/InteractiveMarkerInit.h>
00046
00047 #include <message_filters/subscriber.h>
00048 #include <tf/message_filter.h>
00049
00050 namespace Ogre
00051 {
00052 class SceneManager;
00053 class SceneNode;
00054 }
00055
00056 namespace ogre_tools
00057 {
00058 class Object;
00059 }
00060
00061 namespace rviz
00062 {
00063
00064 class MarkerSelectionHandler;
00065 typedef boost::shared_ptr<MarkerSelectionHandler> MarkerSelectionHandlerPtr;
00066
00067 class MarkerBase;
00068 typedef boost::shared_ptr<MarkerBase> MarkerBasePtr;
00069
00070 typedef std::pair<std::string, int32_t> MarkerID;
00071
00078 class InteractiveMarkerDisplay : public Display, public InteractiveMarkerReceiver
00079 {
00080 public:
00081 InteractiveMarkerDisplay();
00082 virtual ~InteractiveMarkerDisplay();
00083
00084 virtual void onInitialize();
00085
00086 virtual void update(float wall_dt, float ros_dt);
00087
00088 virtual void targetFrameChanged();
00089 virtual void fixedFrameChanged();
00090 virtual void reset();
00091
00092 void setMarkerUpdateTopic(const std::string& topic);
00093 const std::string& getMarkerUpdateTopic() { return marker_update_topic_; }
00094
00095 virtual void createProperties();
00096
00097 bool getShowDescriptions() { return show_descriptions_; }
00098 void setShowDescriptions( bool show );
00099
00100 bool getShowToolTips() { return show_tool_tips_; }
00101 void setShowToolTips( bool show );
00102
00103 bool getShowAxes() { return show_axes_; }
00104 void setShowAxes( bool show );
00105
00107 void setStatusOk(const std::string& name, const std::string& text);
00108 void setStatusWarn(const std::string& name, const std::string& text);
00109 void setStatusError(const std::string& name, const std::string& text);
00110
00115 bool subscribeToInit();
00116
00117
00118 void clearMarkers();
00119
00120
00121 void processMarkerChanges( const std::vector<visualization_msgs::InteractiveMarker>* markers = NULL,
00122 const std::vector<visualization_msgs::InteractiveMarkerPose>* poses = NULL,
00123 const std::vector<std::string>* erases = NULL );
00124
00125 void unsubscribeFromInit();
00126
00127 protected:
00128
00129 virtual void onEnable();
00130 virtual void onDisable();
00131
00132
00133 void subscribe();
00134
00135
00136 void unsubscribe();
00137
00138
00139 void tfMarkerSuccess(const visualization_msgs::InteractiveMarker::ConstPtr& marker);
00140
00141
00142 void tfMarkerFail(const visualization_msgs::InteractiveMarker::ConstPtr& marker, tf::FilterFailureReason reason);
00143
00144
00145 void tfPoseSuccess(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose);
00146
00147
00148 void tfPoseFail(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose, tf::FilterFailureReason reason);
00149
00150 void updateMarker( visualization_msgs::InteractiveMarker::ConstPtr& marker );
00151 void updatePose( visualization_msgs::InteractiveMarkerPose::ConstPtr& pose );
00152
00153 InteractiveMarkerClient im_client_;
00154
00155
00156 Ogre::SceneNode* scene_node_;
00157
00158 typedef boost::shared_ptr<InteractiveMarker> InteractiveMarkerPtr;
00159 typedef std::map< std::string, InteractiveMarkerPtr > M_StringToInteractiveMarkerPtr;
00160 M_StringToInteractiveMarkerPtr interactive_markers_;
00161
00162
00163
00164 tf::MessageFilter<visualization_msgs::InteractiveMarker>* tf_filter_;
00165 tf::MessageFilter<visualization_msgs::InteractiveMarkerPose>* tf_pose_filter_;
00166
00167 ros::Subscriber marker_update_sub_;
00168 ros::Subscriber marker_init_sub_;
00169
00170
00171 typedef std::vector<visualization_msgs::InteractiveMarker::ConstPtr> V_InteractiveMarkerMessage;
00172 V_InteractiveMarkerMessage marker_queue_;
00173 typedef std::vector<visualization_msgs::InteractiveMarkerPose::ConstPtr> V_InteractiveMarkerPoseMessage;
00174 V_InteractiveMarkerPoseMessage pose_queue_;
00175 boost::mutex queue_mutex_;
00176
00177 unsigned num_publishers_;
00178
00179 std::string client_id_;
00180
00181
00182
00183 std::string marker_update_topic_;
00184 ROSTopicStringPropertyWPtr marker_update_topic_property_;
00185
00186 bool show_descriptions_;
00187 BoolPropertyWPtr show_descriptions_property_;
00188
00189 bool show_tool_tips_;
00190 BoolPropertyWPtr show_tool_tips_property_;
00191
00192 bool show_axes_;
00193 BoolPropertyWPtr show_axes_property_;
00194 };
00195
00196 }
00197
00198 #endif