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( const std::string& name, VisualizationManager* manager );
00082 virtual ~InteractiveMarkerDisplay();
00083
00084 virtual void update(float wall_dt, float ros_dt);
00085
00086 virtual void targetFrameChanged();
00087 virtual void fixedFrameChanged();
00088 virtual void reset();
00089
00090 void setMarkerUpdateTopic(const std::string& topic);
00091 const std::string& getMarkerUpdateTopic() { return marker_update_topic_; }
00092
00093 virtual void createProperties();
00094
00095 bool getShowDescriptions() { return show_descriptions_; }
00096 void setShowDescriptions( bool show );
00097
00098 bool getShowToolTips() { return show_tool_tips_; }
00099 void setShowToolTips( bool show );
00100
00101 bool getShowAxes() { return show_axes_; }
00102 void setShowAxes( bool show );
00103
00105 void setStatusOk(const std::string& name, const std::string& text);
00106 void setStatusWarn(const std::string& name, const std::string& text);
00107 void setStatusError(const std::string& name, const std::string& text);
00108
00113 bool subscribeToInit();
00114
00115
00116 void clearMarkers();
00117
00118
00119 void processMarkerChanges( const std::vector<visualization_msgs::InteractiveMarker>* markers = NULL,
00120 const std::vector<visualization_msgs::InteractiveMarkerPose>* poses = NULL,
00121 const std::vector<std::string>* erases = NULL );
00122
00123 void unsubscribeFromInit();
00124
00125 protected:
00126
00127 virtual void onEnable();
00128 virtual void onDisable();
00129
00130
00131 void subscribe();
00132
00133
00134 void unsubscribe();
00135
00136
00137 void tfMarkerSuccess(const visualization_msgs::InteractiveMarker::ConstPtr& marker);
00138
00139
00140 void tfMarkerFail(const visualization_msgs::InteractiveMarker::ConstPtr& marker, tf::FilterFailureReason reason);
00141
00142
00143 void tfPoseSuccess(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose);
00144
00145
00146 void tfPoseFail(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose, tf::FilterFailureReason reason);
00147
00148 void updateMarker( visualization_msgs::InteractiveMarker::ConstPtr& marker );
00149 void updatePose( visualization_msgs::InteractiveMarkerPose::ConstPtr& pose );
00150
00151 InteractiveMarkerClient im_client_;
00152
00153
00154 Ogre::SceneNode* scene_node_;
00155
00156 typedef boost::shared_ptr<InteractiveMarker> InteractiveMarkerPtr;
00157 typedef std::map< std::string, InteractiveMarkerPtr > M_StringToInteractiveMarkerPtr;
00158 M_StringToInteractiveMarkerPtr interactive_markers_;
00159
00160
00161
00162 tf::MessageFilter<visualization_msgs::InteractiveMarker> tf_filter_;
00163 tf::MessageFilter<visualization_msgs::InteractiveMarkerPose> tf_pose_filter_;
00164
00165 ros::Subscriber marker_update_sub_;
00166 ros::Subscriber marker_init_sub_;
00167
00168
00169 typedef std::vector<visualization_msgs::InteractiveMarker::ConstPtr> V_InteractiveMarkerMessage;
00170 V_InteractiveMarkerMessage marker_queue_;
00171 typedef std::vector<visualization_msgs::InteractiveMarkerPose::ConstPtr> V_InteractiveMarkerPoseMessage;
00172 V_InteractiveMarkerPoseMessage pose_queue_;
00173 boost::mutex queue_mutex_;
00174
00175 unsigned num_publishers_;
00176
00177 std::string client_id_;
00178
00179
00180
00181 std::string marker_update_topic_;
00182 ROSTopicStringPropertyWPtr marker_update_topic_property_;
00183
00184 bool show_descriptions_;
00185 BoolPropertyWPtr show_descriptions_property_;
00186
00187 bool show_tool_tips_;
00188 BoolPropertyWPtr show_tool_tips_property_;
00189
00190 bool show_axes_;
00191 BoolPropertyWPtr show_axes_property_;
00192 };
00193
00194 }
00195
00196 #endif