submaps_display.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_RVIZ_SRC_SUBMAPS_DISPLAY_H_
00018 #define CARTOGRAPHER_RVIZ_SRC_SUBMAPS_DISPLAY_H_
00019 
00020 #include <map>
00021 #include <memory>
00022 #include <string>
00023 #include <vector>
00024 
00025 #include "absl/synchronization/mutex.h"
00026 #include "cartographer/common/port.h"
00027 #include "cartographer_ros_msgs/SubmapList.h"
00028 #include "cartographer_rviz/drawable_submap.h"
00029 #include "rviz/message_filter_display.h"
00030 #include "rviz/properties/bool_property.h"
00031 #include "rviz/properties/float_property.h"
00032 #include "tf2_ros/buffer.h"
00033 #include "tf2_ros/transform_listener.h"
00034 
00035 namespace cartographer_rviz {
00036 
00037 // TODO(gaschler): This should be a private class in SubmapsDisplay,
00038 // unfortunately, QT does not allow for this. Move the logic out of the struct
00039 // and use just one slot for all changes.
00040 struct Trajectory : public QObject {
00041   Q_OBJECT
00042 
00043  public:
00044   Trajectory(std::unique_ptr<::rviz::BoolProperty> property,
00045              bool pose_markers_enabled);
00046 
00047   std::unique_ptr<::rviz::BoolProperty> visibility;
00048   std::unique_ptr<::rviz::BoolProperty> pose_markers_visibility;
00049   std::map<int, std::unique_ptr<DrawableSubmap>> submaps;
00050 
00051  private Q_SLOTS:
00052   void AllEnabledToggled();
00053   void PoseMarkersEnabledToggled();
00054 };
00055 
00056 // RViz plugin used for displaying maps which are represented by a collection of
00057 // submaps.
00058 //
00059 // We show an X-ray view of the map which is achieved by shipping textures for
00060 // every submap containing pre-multiplied alpha and grayscale values, these are
00061 // then alpha blended together.
00062 class SubmapsDisplay
00063     : public ::rviz::MessageFilterDisplay<::cartographer_ros_msgs::SubmapList> {
00064   Q_OBJECT
00065 
00066  public:
00067   SubmapsDisplay();
00068   ~SubmapsDisplay() override;
00069 
00070   SubmapsDisplay(const SubmapsDisplay&) = delete;
00071   SubmapsDisplay& operator=(const SubmapsDisplay&) = delete;
00072 
00073  private Q_SLOTS:
00074   void Reset();
00075   void AllEnabledToggled();
00076   void PoseMarkersEnabledToggled();
00077   void ResolutionToggled();
00078 
00079  private:
00080   void CreateClient();
00081 
00082   // These are called by RViz and therefore do not adhere to the style guide.
00083   void onInitialize() override;
00084   void reset() override;
00085   void processMessage(
00086       const ::cartographer_ros_msgs::SubmapList::ConstPtr& msg) override;
00087   void update(float wall_dt, float ros_dt) override;
00088 
00089   ::tf2_ros::Buffer tf_buffer_;
00090   ::tf2_ros::TransformListener tf_listener_;
00091   ros::ServiceClient client_;
00092   ::rviz::StringProperty* submap_query_service_property_;
00093   std::unique_ptr<std::string> map_frame_;
00094   ::rviz::StringProperty* tracking_frame_property_;
00095   Ogre::SceneNode* map_node_ = nullptr;  // Represents the map frame.
00096   std::map<int, std::unique_ptr<Trajectory>> trajectories_ GUARDED_BY(mutex_);
00097   absl::Mutex mutex_;
00098   ::rviz::BoolProperty* slice_high_resolution_enabled_;
00099   ::rviz::BoolProperty* slice_low_resolution_enabled_;
00100   ::rviz::Property* trajectories_category_;
00101   ::rviz::BoolProperty* visibility_all_enabled_;
00102   ::rviz::BoolProperty* pose_markers_all_enabled_;
00103   ::rviz::FloatProperty* fade_out_start_distance_in_meters_;
00104 };
00105 
00106 }  // namespace cartographer_rviz
00107 
00108 #endif  // CARTOGRAPHER_RVIZ_SRC_SUBMAPS_DISPLAY_H_


cartographer_rviz
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:34