moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
interactive_marker_display.h
Go to the documentation of this file.
1/*
2 * Copyright (c) 2008, Willow Garage, Inc.
3 * Copyright (c) 2019, Open Source Robotics Foundation, Inc.
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions are met:
8 *
9 * * Redistributions of source code must retain the above copyright
10 * notice, this list of conditions and the following disclaimer.
11 * * Redistributions in binary form must reproduce the above copyright
12 * notice, this list of conditions and the following disclaimer in the
13 * documentation and/or other materials provided with the distribution.
14 * * Neither the name of the copyright holder nor the names of its
15 * contributors may be used to endorse or promote products derived from
16 * this software without specific prior written permission.
17 *
18 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 * POSSIBILITY OF SUCH DAMAGE.
29 */
30
31// TODO(JafarAbdi): Remove this file once the lag issue is fixed upstream https://github.com/ros2/rviz/issues/548
32// This file is copied from https://github.com/ros2/rviz, the only difference is the addition of the private members
33// pnode_, private_executor_, and private_executor_thread_ to fix the lag in the motion planning display interactive
34// marker cause by Rviz having only a single thread executor
35
36#pragma once
37
38#include <map>
39#include <memory>
40#include <string>
41#include <vector>
42
43#include <visualization_msgs/msg/interactive_marker.hpp>
44#include <visualization_msgs/msg/interactive_marker_update.hpp>
45#include <visualization_msgs/msg/interactive_marker_init.hpp>
46
47#ifndef Q_MOC_RUN
48#include <interactive_markers/interactive_marker_client.hpp>
49#endif
50
51#include <rviz_common/display.hpp>
52
53#include <rviz_default_plugins/displays/interactive_markers/interactive_marker.hpp>
54
55namespace rviz_common
56{
57class BoolProperty;
58class Object;
59} // namespace rviz_common
60
62{
63class InteractiveMarkerNamespaceProperty;
64
65namespace displays
66{
67class MarkerBase;
68
70class InteractiveMarkerDisplay : public rviz_common::Display
71{
72 Q_OBJECT
73
74public:
77 {
78 private_executor_->cancel();
79 if (private_executor_thread_.joinable())
80 private_executor_thread_.join();
81 private_executor_.reset();
82 }
83
84 // Overrides from Display
85 void update(float wall_dt, float ros_dt) override;
86
87 void reset() override;
88
89protected:
90 // Overrides from Display
91 void fixedFrameChanged() override;
92
93 void onInitialize() override;
94
95 void onEnable() override;
96
97 void onDisable() override;
98
99protected Q_SLOTS:
100 void namespaceChanged();
102 void updateShowAxes();
105 void publishFeedback(visualization_msgs::msg::InteractiveMarkerFeedback& feedback);
106 void onStatusUpdate(rviz_common::properties::StatusProperty::Level level, const std::string& name,
107 const std::string& text);
108
109private:
111 void subscribe();
112
114 void unsubscribe();
115
117 void initializeCallback(const visualization_msgs::srv::GetInteractiveMarkers::Response::SharedPtr& /*msg*/);
118
120 void updateCallback(const visualization_msgs::msg::InteractiveMarkerUpdate::ConstSharedPtr& msg);
121
123 void resetCallback();
124
126 void statusCallback(interactive_markers::InteractiveMarkerClient::Status /*status*/, const std::string& message);
127
128 void updateMarkers(const std::vector<visualization_msgs::msg::InteractiveMarker>& markers);
129
130 void updatePoses(const std::vector<visualization_msgs::msg::InteractiveMarkerPose>& marker_poses);
131
133 void eraseAllMarkers();
134
136
139 void eraseMarkers(const std::vector<std::string>& names);
140
141 std::map<std::string, InteractiveMarker::SharedPtr> interactive_markers_map_;
142
143 // Properties
144 InteractiveMarkerNamespaceProperty* interactive_marker_namespace_property_;
145 rviz_common::properties::BoolProperty* show_descriptions_property_;
146 rviz_common::properties::BoolProperty* show_axes_property_;
147 rviz_common::properties::BoolProperty* show_visual_aids_property_;
148 rviz_common::properties::BoolProperty* enable_transparency_property_;
149
150 std::unique_ptr<interactive_markers::InteractiveMarkerClient> interactive_marker_client_;
151
152 std::shared_ptr<rclcpp::Node> pnode_;
153 std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> private_executor_;
154 std::thread private_executor_thread_;
155}; // class InteractiveMarkerDisplay
156
157} // namespace displays
158} // namespace rviz_default_plugins
void publishFeedback(visualization_msgs::msg::InteractiveMarkerFeedback &feedback)
void onStatusUpdate(rviz_common::properties::StatusProperty::Level level, const std::string &name, const std::string &text)