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