78 private_executor_->cancel();
79 if (private_executor_thread_.joinable())
80 private_executor_thread_.join();
81 private_executor_.reset();
85 void update(
float wall_dt,
float ros_dt)
override;
87 void reset()
override;
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);
117 void initializeCallback(
const visualization_msgs::srv::GetInteractiveMarkers::Response::SharedPtr& );
120 void updateCallback(
const visualization_msgs::msg::InteractiveMarkerUpdate::ConstSharedPtr& msg);
123 void resetCallback();
126 void statusCallback(interactive_markers::InteractiveMarkerClient::Status ,
const std::string& message);
128 void updateMarkers(
const std::vector<visualization_msgs::msg::InteractiveMarker>& markers);
130 void updatePoses(
const std::vector<visualization_msgs::msg::InteractiveMarkerPose>& marker_poses);
133 void eraseAllMarkers();
139 void eraseMarkers(
const std::vector<std::string>& names);
141 std::map<std::string, InteractiveMarker::SharedPtr> interactive_markers_map_;
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_;
150 std::unique_ptr<interactive_markers::InteractiveMarkerClient> interactive_marker_client_;
152 std::shared_ptr<rclcpp::Node> pnode_;
153 std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> private_executor_;
154 std::thread private_executor_thread_;