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 #include "rviz/selection/forwards.h"
00034
00035 #include "interactive_marker_control.h"
00036
00037 #include <rviz/ogre_helpers/axes.h>
00038
00039 #include <visualization_msgs/InteractiveMarker.h>
00040 #include <visualization_msgs/InteractiveMarkerPose.h>
00041 #include <visualization_msgs/InteractiveMarkerFeedback.h>
00042
00043 #include <geometry_msgs/Pose.h>
00044
00045 #include <OGRE/OgreVector3.h>
00046 #include <OGRE/OgreQuaternion.h>
00047
00048 #include <boost/shared_ptr.hpp>
00049
00050 #include <ros/publisher.h>
00051
00052 namespace Ogre {
00053 class SceneNode;
00054 }
00055
00056 class QMenu;
00057
00058 namespace rviz
00059 {
00060 class VisualizationManager;
00061 class InteractiveMarkerDisplay;
00062
00063 class InteractiveMarker : public QObject
00064 {
00065 Q_OBJECT
00066 public:
00067 InteractiveMarker( InteractiveMarkerDisplay *owner, VisualizationManager *vis_manager, std::string topic_ns, std::string client_id );
00068 virtual ~InteractiveMarker();
00069
00070
00071
00072 bool processMessage( visualization_msgs::InteractiveMarkerConstPtr message );
00073
00074
00075
00076 void processMessage( visualization_msgs::InteractiveMarkerPoseConstPtr message );
00077
00078
00079 void update(float wall_dt);
00080
00081
00082 void setReferencePose( Ogre::Vector3 position, Ogre::Quaternion orientation );
00083
00084
00085
00086 void setPose( Ogre::Vector3 position, Ogre::Quaternion orientation, const std::string &control_name );
00087
00088 void translate( Ogre::Vector3 delta_position, const std::string &control_name );
00089 void rotate( Ogre::Quaternion delta_orientation, const std::string &control_name );
00090
00091
00092 void requestPoseUpdate( Ogre::Vector3 position, Ogre::Quaternion orientation );
00093
00094 void startDragging();
00095 void stopDragging();
00096
00097 const Ogre::Vector3& getPosition() { return position_; }
00098 const Ogre::Quaternion& getOrientation() { return orientation_; }
00099
00100 float getSize() { return scale_; }
00101 const std::string &getReferenceFrame() { return reference_frame_; }
00102 const std::string& getName() { return name_; }
00103
00104
00105 void setShowDescription( bool show );
00106
00107
00108 void setShowAxes( bool show );
00109
00110
00111 bool handleMouseEvent(ViewportMouseEvent& event, const std::string &control_name );
00112
00113
00114 void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback,
00115 bool mouse_point_valid = false,
00116 const Ogre::Vector3& mouse_point_rel_world = Ogre::Vector3(0,0,0) );
00117
00118 void hideVisible();
00119
00120 void restoreVisible();
00121
00122 protected Q_SLOTS:
00123 void handleMenuSelect( int menu_item_id );
00124
00125 protected:
00126
00127 void publishPose();
00128
00129 void reset();
00130
00131 void updateReferencePose();
00132
00133 QString makeMenuString( const std::string &entry );
00134
00135
00136
00137
00138 void populateMenu( QMenu* menu, std::vector<uint32_t>& ids );
00139
00140 InteractiveMarkerDisplay *owner_;
00141 VisualizationManager *vis_manager_;
00142
00143
00144 std::string reference_frame_;
00145 ros::Time reference_time_;
00146 bool frame_locked_;
00147
00148
00149 Ogre::SceneNode *reference_node_;
00150
00151
00152 Ogre::Vector3 position_;
00153 Ogre::Quaternion orientation_;
00154
00155
00156 bool pose_changed_;
00157 double time_since_last_feedback_;
00158
00159 typedef boost::shared_ptr<InteractiveMarkerControl> InteractiveMarkerControlPtr;
00160 typedef std::map<std::string, InteractiveMarkerControlPtr> M_ControlPtr;
00161 M_ControlPtr controls_;
00162
00163 std::string name_;
00164 std::string description_;
00165
00166 bool dragging_;
00167 std::string old_target_frame_;
00168
00169
00170 bool pose_update_requested_;
00171 Ogre::Vector3 requested_position_;
00172 Ogre::Quaternion requested_orientation_;
00173
00174 float scale_;
00175
00176 boost::shared_ptr<QMenu> menu_;
00177
00178
00179 struct MenuNode
00180 {
00181 visualization_msgs::MenuEntry entry;
00182 std::vector<uint32_t> child_ids;
00183 };
00184
00185
00186 std::map< uint32_t, MenuNode > menu_entries_;
00187
00188
00189 std::vector<uint32_t> top_level_menu_ids_;
00190
00191
00192 std::string last_control_name_;
00193
00194 double heart_beat_t_;
00195
00196
00197
00198 Axes *axes_;
00199 Ogre::SceneNode *axes_node_;
00200
00201 InteractiveMarkerControlPtr description_control_;
00202
00203 ros::Publisher feedback_pub_;
00204 std::string topic_ns_;
00205 std::string client_id_;
00206
00207 boost::recursive_mutex mutex_;
00208
00209 boost::shared_ptr< boost::thread > sys_thread_;
00210
00211 bool got_3d_point_for_menu_;
00212 Ogre::Vector3 three_d_point_for_menu_;
00213 };
00214
00215
00216 }
00217
00218 #endif