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> 39 #include <OgreVector3.h> 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> 65 class InteractiveMarkerDisplay;
76 bool processMessage(
const visualization_msgs::InteractiveMarker& message );
80 void processMessage(
const visualization_msgs::InteractiveMarkerPose& message );
83 void update(
float wall_dt);
87 void setPose( Ogre::Vector3 position, Ogre::Quaternion orientation,
const std::string &control_name );
89 void translate( Ogre::Vector3 delta_position,
const std::string &control_name );
90 void rotate( Ogre::Quaternion delta_orientation,
const std::string &control_name );
93 void requestPoseUpdate( Ogre::Vector3 position, Ogre::Quaternion orientation );
103 const std::string&
getName() {
return name_; }
106 void setShowDescription(
bool show );
109 void setShowAxes(
bool show );
112 void setShowVisualAids(
bool show );
126 bool handle3DCursorEvent(
ViewportMouseEvent& event,
const Ogre::Vector3& cursor_pos,
const Ogre::Quaternion& cursor_rot,
const std::string &control_name);
137 void showMenu(
ViewportMouseEvent& event,
const std::string &control_name,
const Ogre::Vector3 &three_d_point,
bool valid_point );
140 void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback,
141 bool mouse_point_valid =
false,
142 const Ogre::Vector3& mouse_point_rel_world = Ogre::Vector3(0,0,0) );
151 void userFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
155 void handleMenuSelect(
int menu_item_id );
164 void updateReferencePose();
166 QString makeMenuString(
const std::string &entry );
171 void populateMenu( QMenu* menu, std::vector<uint32_t>& ids );
192 typedef std::map<std::string, InteractiveMarkerControlPtr>
M_ControlPtr;
213 visualization_msgs::MenuEntry
entry;
boost::recursive_mutex mutex_
double time_since_last_feedback_
std::map< uint32_t, MenuNode > menu_entries_
const Ogre::Quaternion & getOrientation()
std::string last_control_name_
Ogre::Vector3 three_d_point_for_menu_
Ogre::Vector3 requested_position_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
const Ogre::Vector3 & getPosition()
Pure-virtual base class for objects which give Display subclasses context in which to work...
const std::string & getName()
std::map< std::string, InteractiveMarkerControlPtr > M_ControlPtr
Ogre::Quaternion requested_orientation_
InteractiveMarkerControlPtr description_control_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
bool pose_update_requested_
std::vector< uint32_t > top_level_menu_ids_
boost::shared_ptr< boost::thread > sys_thread_
boost::shared_ptr< InteractiveMarkerControl > InteractiveMarkerControlPtr
boost::shared_ptr< QMenu > getMenu()
const std::string & getReferenceFrame()
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const
DisplayContext * context_
std::string reference_frame_
boost::shared_ptr< QMenu > menu_
Ogre::Quaternion orientation_
bool got_3d_point_for_menu_
ros::Time reference_time_
Ogre::SceneNode * reference_node_