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  void onInitialize() override;
72 
73  void update(float wall_dt, float ros_dt) override;
74 
75  void fixedFrameChanged() override;
76 
77  void reset() override;
78 
79  void setTopic(const QString& topic, const QString& datatype) override;
80 
81 protected:
82  void onEnable() override;
83  void onDisable() override;
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  // Subscribe to all message topics
96  void subscribe();
97 
98  // Unsubscribe from all message topics
99  void unsubscribe();
100 
101  void initCb(visualization_msgs::InteractiveMarkerInitConstPtr msg);
102  void updateCb(visualization_msgs::InteractiveMarkerUpdateConstPtr msg);
103 
104  void resetCb(std::string server_id);
105 
107  const std::string& server_id,
108  const std::string& msg);
109 
110  void updateMarkers(const std::string& server_id,
111  const std::vector<visualization_msgs::InteractiveMarker>& markers);
112 
113  void updatePoses(const std::string& server_id,
114  const std::vector<visualization_msgs::InteractiveMarkerPose>& marker_poses);
115 
116  void eraseMarkers(const std::string& server_id, const std::vector<std::string>& names);
117 
118  // Update the display's versions of the markers.
119  void processMarkerChanges(const std::vector<visualization_msgs::InteractiveMarker>* markers = nullptr,
120  const std::vector<visualization_msgs::InteractiveMarkerPose>* poses = nullptr,
121  const std::vector<std::string>* erases = nullptr);
122 
124  typedef std::map<std::string, IMPtr> M_StringToIMPtr;
125  typedef std::map<std::string, M_StringToIMPtr> M_StringToStringToIMPtr;
126  M_StringToStringToIMPtr interactive_markers_;
127 
128  M_StringToIMPtr& getImMap(std::string server_id);
129 
130  std::string client_id_;
131 
132  // Properties
138 
140 
142 
143  std::string topic_ns_;
144 };
145 
146 } // namespace rviz
147 
148 #endif /* RVIZ_MARKER_DISPLAY_H */
void updateMarkers(const std::string &server_id, const std::vector< visualization_msgs::InteractiveMarker > &markers)
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
void initCb(visualization_msgs::InteractiveMarkerInitConstPtr msg)
M_StringToIMPtr & getImMap(std::string server_id)
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void eraseMarkers(const std::string &server_id, const std::vector< std::string > &names)
void updateCb(visualization_msgs::InteractiveMarkerUpdateConstPtr msg)
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
boost::shared_ptr< interactive_markers::InteractiveMarkerClient > im_client_
void statusCb(interactive_markers::InteractiveMarkerClient::StatusT status, const std::string &server_id, const std::string &msg)
void updatePoses(const std::string &server_id, const std::vector< visualization_msgs::InteractiveMarkerPose > &marker_poses)
std::pair< std::string, int32_t > MarkerID
std::map< std::string, IMPtr > M_StringToIMPtr
const char * datatype()
void publishFeedback(visualization_msgs::InteractiveMarkerFeedback &feedback)
void processMarkerChanges(const std::vector< visualization_msgs::InteractiveMarker > *markers=nullptr, const std::vector< visualization_msgs::InteractiveMarkerPose > *poses=nullptr, const std::vector< std::string > *erases=nullptr)
std::map< std::string, M_StringToIMPtr > M_StringToStringToIMPtr
Displays Interactive Markers.
void reset() override
Called to tell the display to clear its state.
boost::shared_ptr< MarkerBase > MarkerBasePtr
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
M_StringToStringToIMPtr interactive_markers_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void onStatusUpdate(StatusProperty::Level level, const std::string &name, const std::string &text)
boost::shared_ptr< InteractiveMarker > IMPtr
void onInitialize() override
Override this function to do subclass-specific initialization.


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24