30 #ifndef RVIZ_INTERACTIVE_MARKER_H_
31 #define RVIZ_INTERACTIVE_MARKER_H_
34 #include <boost/shared_ptr.hpp>
35 #include <boost/thread/mutex.hpp>
36 #include <boost/thread/recursive_mutex.hpp>
37 #include <boost/thread/thread.hpp>
40 #include <OgreQuaternion.h>
43 #include <visualization_msgs/InteractiveMarker.h>
44 #include <visualization_msgs/InteractiveMarkerPose.h>
45 #include <visualization_msgs/InteractiveMarkerFeedback.h>
46 #include <geometry_msgs/Pose.h>
53 #include <rviz/default_plugin/rviz_default_plugin_export.h>
67 class InteractiveMarkerDisplay;
78 bool processMessage(
const visualization_msgs::InteractiveMarker& message);
82 void processMessage(
const visualization_msgs::InteractiveMarkerPose& message);
85 void update(
float wall_dt);
89 void setPose(Ogre::Vector3 position, Ogre::Quaternion orientation,
const std::string& control_name);
91 void translate(Ogre::Vector3 delta_position,
const std::string& control_name);
92 void rotate(Ogre::Quaternion delta_orientation,
const std::string& control_name);
95 void requestPoseUpdate(Ogre::Vector3 position, Ogre::Quaternion orientation);
115 return reference_frame_;
123 void setShowDescription(
bool show);
126 void setShowAxes(
bool show);
129 void setShowVisualAids(
bool show);
145 const Ogre::Vector3& cursor_pos,
146 const Ogre::Quaternion& cursor_rot,
147 const std::string& control_name);
161 const std::string& control_name,
162 const Ogre::Vector3& three_d_point,
166 void publishFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback,
167 bool mouse_point_valid =
false,
168 const Ogre::Vector3& mouse_point_rel_world = Ogre::Vector3(0, 0, 0));
183 void userFeedback(visualization_msgs::InteractiveMarkerFeedback& feedback);
187 void handleMenuSelect(
int menu_item_id);
195 void updateReferencePose();
197 QString makeMenuString(
const std::string& entry);
202 void populateMenu(QMenu* menu, std::vector<uint32_t>& ids);
223 typedef std::map<std::string, InteractiveMarkerControlPtr>
M_ControlPtr;
244 visualization_msgs::MenuEntry
entry;