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_H_
00031 #define RVIZ_INTERACTIVE_MARKER_H_
00032
00033 #ifndef Q_MOC_RUN
00034 #include <boost/shared_ptr.hpp>
00035 #include <boost/thread/mutex.hpp>
00036 #include <boost/thread/recursive_mutex.hpp>
00037 #include <boost/thread/thread.hpp>
00038
00039 #include <OgreVector3.h>
00040 #include <OgreQuaternion.h>
00041 #endif
00042
00043 #include <visualization_msgs/InteractiveMarker.h>
00044 #include <visualization_msgs/InteractiveMarkerPose.h>
00045 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00046 #include <geometry_msgs/Pose.h>
00047
00048 #include <ros/publisher.h>
00049
00050 #include "rviz/selection/forwards.h"
00051 #include "rviz/ogre_helpers/axes.h"
00052
00053 #include "rviz/default_plugin/interactive_markers/interactive_marker_control.h"
00054 #include "rviz/properties/status_property.h"
00055
00056 namespace Ogre {
00057 class SceneNode;
00058 }
00059
00060 class QMenu;
00061
00062 namespace rviz
00063 {
00064 class DisplayContext;
00065 class InteractiveMarkerDisplay;
00066
00067 class InteractiveMarker : public QObject
00068 {
00069 Q_OBJECT
00070 public:
00071 InteractiveMarker( Ogre::SceneNode* scene_node, DisplayContext* context );
00072 virtual ~InteractiveMarker();
00073
00074
00075
00076 bool processMessage( const visualization_msgs::InteractiveMarker& message );
00077
00078
00079
00080 void processMessage( const visualization_msgs::InteractiveMarkerPose& message );
00081
00082
00083 void update(float wall_dt);
00084
00085
00086
00087 void setPose( Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name );
00088
00089 void translate( Ogre::Vector3 delta_position, const std::string &control_name );
00090 void rotate( Ogre::Quaternion delta_orientation, const std::string &control_name );
00091
00092
00093 void requestPoseUpdate( Ogre::Vector3 position, Ogre::Quaternion orientation );
00094
00095 void startDragging();
00096 void stopDragging();
00097
00098 const Ogre::Vector3& getPosition() { return position_; }
00099 const Ogre::Quaternion& getOrientation() { return orientation_; }
00100
00101 float getSize() { return scale_; }
00102 const std::string &getReferenceFrame() { return reference_frame_; }
00103 const std::string& getName() { return name_; }
00104
00105
00106 void setShowDescription( bool show );
00107
00108
00109 void setShowAxes( bool show );
00110
00111
00112 void setShowVisualAids( bool show );
00113
00114
00115 bool handleMouseEvent(ViewportMouseEvent& event, const std::string &control_name );
00116
00126 bool handle3DCursorEvent(ViewportMouseEvent& event, const Ogre::Vector3& cursor_pos, const Ogre::Quaternion& cursor_rot, const std::string &control_name);
00127
00128
00137 void showMenu( ViewportMouseEvent& event, const std::string &control_name, const Ogre::Vector3 &three_d_point, bool valid_point );
00138
00139
00140 void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback,
00141 bool mouse_point_valid = false,
00142 const Ogre::Vector3& mouse_point_rel_world = Ogre::Vector3(0,0,0) );
00143
00144 bool hasMenu() { return has_menu_; }
00145
00147 boost::shared_ptr<QMenu> getMenu() { return menu_; }
00148
00149 Q_SIGNALS:
00150
00151 void userFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
00152 void statusUpdate( StatusProperty::Level level, const std::string& name, const std::string& text );
00153
00154 protected Q_SLOTS:
00155 void handleMenuSelect( int menu_item_id );
00156
00157 protected:
00158
00159 void publishPose();
00160
00161 void reset();
00162
00163
00164 void updateReferencePose();
00165
00166 QString makeMenuString( const std::string &entry );
00167
00168
00169
00170
00171 void populateMenu( QMenu* menu, std::vector<uint32_t>& ids );
00172
00173 DisplayContext* context_;
00174
00175
00176 std::string reference_frame_;
00177 ros::Time reference_time_;
00178 bool frame_locked_;
00179
00180
00181 Ogre::SceneNode *reference_node_;
00182
00183
00184 Ogre::Vector3 position_;
00185 Ogre::Quaternion orientation_;
00186
00187
00188 bool pose_changed_;
00189 double time_since_last_feedback_;
00190
00191 typedef boost::shared_ptr<InteractiveMarkerControl> InteractiveMarkerControlPtr;
00192 typedef std::map<std::string, InteractiveMarkerControlPtr> M_ControlPtr;
00193 M_ControlPtr controls_;
00194
00195 std::string name_;
00196 std::string description_;
00197
00198 bool dragging_;
00199
00200
00201 bool pose_update_requested_;
00202 Ogre::Vector3 requested_position_;
00203 Ogre::Quaternion requested_orientation_;
00204
00205 float scale_;
00206
00207 boost::shared_ptr<QMenu> menu_;
00208 bool has_menu_;
00209
00210
00211 struct MenuNode
00212 {
00213 visualization_msgs::MenuEntry entry;
00214 std::vector<uint32_t> child_ids;
00215 };
00216
00217
00218 std::map< uint32_t, MenuNode > menu_entries_;
00219
00220
00221 std::vector<uint32_t> top_level_menu_ids_;
00222
00223
00224 std::string last_control_name_;
00225
00226 double heart_beat_t_;
00227
00228
00229
00230 Axes *axes_;
00231
00232 InteractiveMarkerControlPtr description_control_;
00233
00234 std::string topic_ns_;
00235 std::string client_id_;
00236
00237 boost::recursive_mutex mutex_;
00238
00239 boost::shared_ptr< boost::thread > sys_thread_;
00240
00241 bool got_3d_point_for_menu_;
00242 Ogre::Vector3 three_d_point_for_menu_;
00243
00244 bool show_visual_aids_;
00245 };
00246
00247
00248 }
00249
00250 #endif