interactive_marker_display.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef RVIZ_INTERACTIVE_MARKER_DISPLAY_H
31 #define RVIZ_INTERACTIVE_MARKER_DISPLAY_H
32 
33 #include <map>
34 #include <set>
35 
36 #include <visualization_msgs/InteractiveMarker.h>
37 #include <visualization_msgs/InteractiveMarkerUpdate.h>
38 #include <visualization_msgs/InteractiveMarkerInit.h>
39 
40 #ifndef Q_MOC_RUN
42 #include <tf/message_filter.h>
44 #endif
45 
46 #include "rviz/display.h"
48 
50 
51 namespace rviz
52 {
53 class BoolProperty;
54 class Object;
55 class RosTopicProperty;
56 class MarkerBase;
57 
59 typedef std::pair<std::string, int32_t> MarkerID;
60 
66 {
67 Q_OBJECT
68 public:
70 
71  virtual void onInitialize();
72 
73  virtual void update(float wall_dt, float ros_dt);
74 
75  virtual void fixedFrameChanged();
76 
77  virtual void reset();
78 
79  virtual void setTopic( const QString &topic, const QString &datatype );
80 
81 protected:
82  virtual void onEnable();
83  virtual void onDisable();
84 
85 protected Q_SLOTS:
86  void updateTopic();
88  void updateShowAxes();
89  void updateShowVisualAids();
91  void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback);
92  void onStatusUpdate( StatusProperty::Level level, const std::string& name, const std::string& text );
93 
94 private:
95 
96  // Subscribe to all message topics
97  void subscribe();
98 
99  // Unsubscribe from all message topics
100  void unsubscribe();
101 
102  void initCb( visualization_msgs::InteractiveMarkerInitConstPtr msg );
103  void updateCb( visualization_msgs::InteractiveMarkerUpdateConstPtr msg );
104 
105  void resetCb( std::string server_id );
106 
108  const std::string& server_id,
109  const std::string& msg );
110 
111  void updateMarkers(
112  const std::string& server_id,
113  const std::vector<visualization_msgs::InteractiveMarker>& markers );
114 
115  void updatePoses(
116  const std::string& server_id,
117  const std::vector<visualization_msgs::InteractiveMarkerPose>& marker_poses );
118 
119  void eraseMarkers(
120  const std::string& server_id,
121  const std::vector<std::string>& names );
122 
123  // Update the display's versions of the markers.
124  void processMarkerChanges( const std::vector<visualization_msgs::InteractiveMarker>* markers = NULL,
125  const std::vector<visualization_msgs::InteractiveMarkerPose>* poses = NULL,
126  const std::vector<std::string>* erases = NULL );
127 
129  typedef std::map< std::string, IMPtr > M_StringToIMPtr;
130  typedef std::map< std::string, M_StringToIMPtr > M_StringToStringToIMPtr;
131  M_StringToStringToIMPtr interactive_markers_;
132 
133  M_StringToIMPtr& getImMap( std::string server_id );
134 
135  std::string client_id_;
136 
137  // Properties
143 
145 
147 
148  std::string topic_ns_;
149 };
150 
151 } // namespace rviz
152 
153 #endif /* RVIZ_MARKER_DISPLAY_H */
std::map< std::string, IMPtr > M_StringToIMPtr
#define NULL
Definition: global.h:37
virtual void reset()
Called to tell the display to clear its state.
void updateMarkers(const std::string &server_id, const std::vector< visualization_msgs::InteractiveMarker > &markers)
std::map< std::string, M_StringToIMPtr > M_StringToStringToIMPtr
void statusCb(interactive_markers::InteractiveMarkerClient::StatusT, const std::string &server_id, const std::string &msg)
void initCb(visualization_msgs::InteractiveMarkerInitConstPtr msg)
M_StringToIMPtr & getImMap(std::string server_id)
void eraseMarkers(const std::string &server_id, const std::vector< std::string > &names)
void updateCb(visualization_msgs::InteractiveMarkerUpdateConstPtr msg)
boost::shared_ptr< interactive_markers::InteractiveMarkerClient > im_client_
void updatePoses(const std::string &server_id, const std::vector< visualization_msgs::InteractiveMarkerPose > &marker_poses)
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
std::pair< std::string, int32_t > MarkerID
virtual void setTopic(const QString &topic, const QString &datatype)
Set the ROS topic to listen to for this display.
void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
virtual void onInitialize()
Override this function to do subclass-specific initialization.
void processMarkerChanges(const std::vector< visualization_msgs::InteractiveMarker > *markers=NULL, const std::vector< visualization_msgs::InteractiveMarkerPose > *poses=NULL, const std::vector< std::string > *erases=NULL)
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
Displays Interactive Markers.
boost::shared_ptr< MarkerBase > MarkerBasePtr
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
M_StringToStringToIMPtr interactive_markers_
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void onStatusUpdate(StatusProperty::Level level, const std::string &name, const std::string &text)
boost::shared_ptr< InteractiveMarker > IMPtr


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51