submaps_display.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include "OgreResourceGroupManager.h"
22 #include "cartographer_ros_msgs/SubmapList.h"
23 #include "cartographer_ros_msgs/SubmapQuery.h"
24 #include "geometry_msgs/TransformStamped.h"
26 #include "ros/package.h"
27 #include "ros/ros.h"
28 #include "rviz/display_context.h"
29 #include "rviz/frame_manager.h"
32 
33 namespace cartographer_rviz {
34 
35 namespace {
36 
37 constexpr int kMaxOnGoingRequestsPerTrajectory = 6;
38 constexpr char kMaterialsDirectory[] = "/ogre_media/materials";
39 constexpr char kGlsl120Directory[] = "/glsl120";
40 constexpr char kScriptsDirectory[] = "/scripts";
41 constexpr char kDefaultMapFrame[] = "map";
42 constexpr char kDefaultTrackingFrame[] = "base_link";
43 constexpr char kDefaultSubmapQueryServiceName[] = "/submap_query";
44 
45 } // namespace
46 
47 SubmapsDisplay::SubmapsDisplay() : tf_listener_(tf_buffer_) {
48  submap_query_service_property_ = new ::rviz::StringProperty(
49  "Submap query service", kDefaultSubmapQueryServiceName,
50  "Submap query service to connect to.", this, SLOT(Reset()));
51  map_frame_property_ = new ::rviz::StringProperty(
52  "Map frame", kDefaultMapFrame, "Map frame, used for fading out submaps.",
53  this);
54  tracking_frame_property_ = new ::rviz::StringProperty(
55  "Tracking frame", kDefaultTrackingFrame,
56  "Tracking frame, used for fading out submaps.", this);
57  client_ = update_nh_.serviceClient<::cartographer_ros_msgs::SubmapQuery>("");
58  submaps_category_ = new ::rviz::Property(
59  "Submaps", QVariant(), "List of all submaps, organized by trajectories.",
60  this);
61  visibility_all_enabled_ = new ::rviz::BoolProperty(
62  "All Enabled", true,
63  "Whether all the submaps should be displayed or not.", submaps_category_,
64  SLOT(AllEnabledToggled()), this);
65  const std::string package_path = ::ros::package::getPath(ROS_PACKAGE_NAME);
66  Ogre::ResourceGroupManager::getSingleton().addResourceLocation(
67  package_path + kMaterialsDirectory, "FileSystem", ROS_PACKAGE_NAME);
68  Ogre::ResourceGroupManager::getSingleton().addResourceLocation(
69  package_path + kMaterialsDirectory + kGlsl120Directory, "FileSystem",
71  Ogre::ResourceGroupManager::getSingleton().addResourceLocation(
72  package_path + kMaterialsDirectory + kScriptsDirectory, "FileSystem",
74  Ogre::ResourceGroupManager::getSingleton().initialiseAllResourceGroups();
75 }
76 
78 
80 
82  client_ = update_nh_.serviceClient<::cartographer_ros_msgs::SubmapQuery>(
84 }
85 
88  CreateClient();
89 }
90 
94  client_.shutdown();
95  trajectories_.clear();
96  CreateClient();
97 }
98 
100  const ::cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
102  // In case Cartographer node is relaunched, destroy
103  // trajectories from the previous instance
104  if (msg->trajectory.size() < trajectories_.size()) {
105  trajectories_.clear();
106  }
107  for (size_t trajectory_id = 0; trajectory_id < msg->trajectory.size();
108  ++trajectory_id) {
109  if (trajectory_id >= trajectories_.size()) {
110  // When a trajectory is destroyed, it also needs to delete its rviz
111  // Property object, so we use a unique_ptr for it
112  trajectories_.push_back(Trajectory(
113  ::cartographer::common::make_unique<::rviz::Property>(
114  QString("Trajectory %1").arg(trajectory_id), QVariant(),
115  QString("List of all submaps in Trajectory %1.")
116  .arg(trajectory_id),
118  std::vector<std::unique_ptr<DrawableSubmap>>()));
119  }
120  auto& trajectory_category = trajectories_[trajectory_id].first;
121  auto& trajectory = trajectories_[trajectory_id].second;
122  const std::vector<::cartographer_ros_msgs::SubmapEntry>& submap_entries =
123  msg->trajectory[trajectory_id].submap;
124  // Same as above, destroy the whole trajectory if we detect that
125  // we have more submaps than we should
126  if (submap_entries.size() < trajectory.size()) {
127  trajectory.clear();
128  }
129  for (size_t submap_index = 0; submap_index < submap_entries.size();
130  ++submap_index) {
131  if (submap_index >= trajectory.size()) {
132  trajectory.push_back(
133  ::cartographer::common::make_unique<DrawableSubmap>(
134  trajectory_id, submap_index, context_->getSceneManager(),
135  trajectory_category.get(), visibility_all_enabled_->getBool()));
136  }
137  trajectory[submap_index]->Update(msg->header,
138  submap_entries[submap_index],
140  }
141  }
142 }
143 
144 void SubmapsDisplay::update(const float wall_dt, const float ros_dt) {
146  // Update the fading by z distance.
147  try {
148  const ::geometry_msgs::TransformStamped transform_stamped =
151  ros::Time(0) /* latest */);
152  for (auto& trajectory : trajectories_) {
153  for (auto& submap : trajectory.second) {
154  submap->SetAlpha(transform_stamped.transform.translation.z);
155  }
156  }
157  } catch (const tf2::TransformException& ex) {
158  ROS_WARN("Could not compute submap fading: %s", ex.what());
159  }
160 
161  // Schedule fetching of new submap textures.
162  for (const auto& trajectory : trajectories_) {
163  int num_ongoing_requests = 0;
164  for (const auto& submap : trajectory.second) {
165  if (submap->QueryInProgress()) {
166  ++num_ongoing_requests;
167  }
168  }
169  for (int submap_index = static_cast<int>(trajectory.second.size()) - 1;
170  submap_index >= 0 &&
171  num_ongoing_requests < kMaxOnGoingRequestsPerTrajectory;
172  --submap_index) {
173  if (trajectory.second[submap_index]->MaybeFetchTexture(&client_)) {
174  ++num_ongoing_requests;
175  }
176  }
177  }
178 }
179 
182  const bool visibility = visibility_all_enabled_->getBool();
183  for (auto& trajectory : trajectories_) {
184  for (auto& submap : trajectory.second) {
185  submap->set_visibility(visibility);
186  }
187  }
188 }
189 
190 } // namespace cartographer_rviz
191 
::rviz::Property * submaps_category_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
::cartographer::common::Mutex mutex_
::rviz::StringProperty * tracking_frame_property_
virtual void onInitialize()
DisplayContext * context_
ros::NodeHandle update_nh_
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
#define ROS_WARN(...)
std::string getStdString()
void processMessage(const ::cartographer_ros_msgs::SubmapList::ConstPtr &msg) override
virtual bool getBool() const
virtual FrameManager * getFrameManager() const =0
std::pair< std::unique_ptr<::rviz::Property >, std::vector< std::unique_ptr< DrawableSubmap >>> Trajectory
::rviz::StringProperty * submap_query_service_property_
::rviz::StringProperty * map_frame_property_
::rviz::BoolProperty * visibility_all_enabled_
virtual Ogre::SceneManager * getSceneManager() const =0
Mutex::Locker MutexLocker
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void update(float wall_dt, float ros_dt) override


cartographer_rviz
Author(s):
autogenerated on Mon Jun 10 2019 12:59:49