drawable_submap.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 <chrono>
20 #include <future>
21 #include <sstream>
22 #include <string>
23 
24 #include "Eigen/Core"
25 #include "Eigen/Geometry"
26 #include "OgreGpuProgramParams.h"
27 #include "OgreImage.h"
30 #include "cartographer_ros_msgs/SubmapQuery.h"
32 #include "ros/ros.h"
33 
34 namespace cartographer_rviz {
35 
36 namespace {
37 
38 constexpr std::chrono::milliseconds kMinQueryDelayInMs(250);
39 constexpr char kSubmapTexturePrefix[] = "SubmapTexture";
40 constexpr char kManualObjectPrefix[] = "ManualObjectSubmap";
41 constexpr char kSubmapMaterialPrefix[] = "SubmapMaterial";
42 constexpr char kSubmapSourceMaterialName[] = "cartographer_ros/Submap";
43 
44 // Distance before which the submap will be shown at full opacity, and distance
45 // over which the submap will then fade out.
46 constexpr double kFadeOutStartDistanceInMeters = 1.;
47 constexpr double kFadeOutDistanceInMeters = 2.;
48 constexpr float kAlphaUpdateThreshold = 0.2f;
49 
50 std::string GetSubmapIdentifier(const int trajectory_id,
51  const int submap_index) {
52  return std::to_string(trajectory_id) + "-" + std::to_string(submap_index);
53 }
54 
55 } // namespace
56 
57 DrawableSubmap::DrawableSubmap(const int trajectory_id, const int submap_index,
58  Ogre::SceneManager* const scene_manager,
59  ::rviz::Property* submap_category,
60  const bool visible)
61  : trajectory_id_(trajectory_id),
62  submap_index_(submap_index),
63  scene_manager_(scene_manager),
64  scene_node_(scene_manager->getRootSceneNode()->createChildSceneNode()),
65  manual_object_(scene_manager->createManualObject(
66  kManualObjectPrefix +
67  GetSubmapIdentifier(trajectory_id, submap_index))),
68  last_query_timestamp_(0) {
69  material_ = Ogre::MaterialManager::getSingleton().getByName(
70  kSubmapSourceMaterialName);
71  material_ =
72  material_->clone(kSubmapMaterialPrefix +
73  GetSubmapIdentifier(trajectory_id_, submap_index));
74  material_->setReceiveShadows(false);
75  material_->getTechnique(0)->setLightingEnabled(false);
76  material_->setCullingMode(Ogre::CULL_NONE);
77  material_->setDepthBias(-1.f, 0.f);
78  material_->setDepthWriteEnabled(false);
79  // DrawableSubmap creates and manages its visibility property object
80  // (a unique_ptr is needed because the Qt parent of the visibility
81  // property is the submap_category object - the BoolProperty needs
82  // to be destroyed along with the DrawableSubmap)
83  visibility_ = ::cartographer::common::make_unique<::rviz::BoolProperty>(
84  "" /* title */, visible, "" /* description */, submap_category,
85  SLOT(ToggleVisibility()), this);
86  if (visible) {
87  scene_node_->attachObject(manual_object_);
88  }
89  connect(this, SIGNAL(RequestSucceeded()), this, SLOT(UpdateSceneNode()));
90 }
91 
93  if (QueryInProgress()) {
94  rpc_request_future_.wait();
95  }
96  Ogre::MaterialManager::getSingleton().remove(material_->getHandle());
97  if (!texture_.isNull()) {
98  Ogre::TextureManager::getSingleton().remove(texture_->getHandle());
99  texture_.setNull();
100  }
101  scene_manager_->destroySceneNode(scene_node_);
102  scene_manager_->destroyManualObject(manual_object_);
103 }
104 
106  const ::std_msgs::Header& header,
107  const ::cartographer_ros_msgs::SubmapEntry& metadata,
108  ::rviz::FrameManager* const frame_manager) {
109  Ogre::Vector3 position;
110  Ogre::Quaternion orientation;
111  if (!frame_manager->transform(header, metadata.pose, position, orientation)) {
112  // We don't know where we would display the texture, so we stop here.
113  return;
114  }
116  position_ = position;
117  orientation_ = orientation;
118  submap_z_ = metadata.pose.position.z;
119  metadata_version_ = metadata.submap_version;
120  if (texture_version_ != -1) {
121  // We have to update the transform since we are already displaying a texture
122  // for this submap.
123  UpdateTransform();
124  }
125  visibility_->setName(
126  QString("%1.%2").arg(submap_index_).arg(metadata_version_));
127  visibility_->setDescription(
128  QString("Toggle visibility of this individual submap.<br><br>"
129  "Trajectory %1, submap %2, submap version %3")
130  .arg(trajectory_id_)
131  .arg(submap_index_)
132  .arg(metadata_version_));
133 }
134 
137  // Received metadata version can also be lower - if we restarted Cartographer
138  const bool newer_version_available = texture_version_ != metadata_version_;
139  const std::chrono::milliseconds now =
140  std::chrono::duration_cast<std::chrono::milliseconds>(
141  std::chrono::system_clock::now().time_since_epoch());
142  const bool recently_queried =
143  last_query_timestamp_ + kMinQueryDelayInMs > now;
144  if (!newer_version_available || recently_queried || query_in_progress_) {
145  return false;
146  }
147  query_in_progress_ = true;
148  last_query_timestamp_ = now;
149  rpc_request_future_ = std::async(std::launch::async, [this, client]() {
150  ::cartographer_ros_msgs::SubmapQuery srv;
151  srv.request.trajectory_id = trajectory_id_;
152  srv.request.submap_index = submap_index_;
153  if (client->call(srv)) {
154  // We emit a signal to update in the right thread, and pass via the
155  // 'response_' member to simplify the signal-slot connection slightly.
157  response_ = srv.response;
158  Q_EMIT RequestSucceeded();
159  } else {
161  query_in_progress_ = false;
162  }
163  });
164  return true;
165 }
166 
169  return query_in_progress_;
170 }
171 
172 void DrawableSubmap::SetAlpha(const double current_tracking_z) {
173  const double distance_z = std::abs(submap_z_ - current_tracking_z);
174  const double fade_distance =
175  std::max(distance_z - kFadeOutStartDistanceInMeters, 0.);
176  const float alpha = static_cast<float>(
177  std::max(0., 1. - fade_distance / kFadeOutDistanceInMeters));
178 
179  const Ogre::GpuProgramParametersSharedPtr parameters =
180  material_->getTechnique(0)->getPass(0)->getFragmentProgramParameters();
181  parameters->setNamedConstant("u_alpha", UpdateAlpha(alpha));
182 }
183 
186  texture_version_ = response_.submap_version;
187  std::string compressed_cells(response_.cells.begin(), response_.cells.end());
188  std::string cells;
189  ::cartographer::common::FastGunzipString(compressed_cells, &cells);
190  tf::poseMsgToEigen(response_.slice_pose, slice_pose_);
191  UpdateTransform();
192  query_in_progress_ = false;
193  // The call to Ogre's loadRawData below does not work with an RG texture,
194  // therefore we create an RGB one whose blue channel is always 0.
195  std::vector<char> rgb;
196  for (int i = 0; i < response_.height; ++i) {
197  for (int j = 0; j < response_.width; ++j) {
198  auto r = cells[(i * response_.width + j) * 2];
199  auto g = cells[(i * response_.width + j) * 2 + 1];
200  rgb.push_back(r);
201  rgb.push_back(g);
202  rgb.push_back(0.);
203  }
204  }
205 
206  manual_object_->clear();
207  const float metric_width = response_.resolution * response_.width;
208  const float metric_height = response_.resolution * response_.height;
209  manual_object_->begin(material_->getName(),
210  Ogre::RenderOperation::OT_TRIANGLE_STRIP);
211  // Bottom left
212  manual_object_->position(-metric_height, 0.0f, 0.0f);
213  manual_object_->textureCoord(0.0f, 1.0f);
214  // Bottom right
215  manual_object_->position(-metric_height, -metric_width, 0.0f);
216  manual_object_->textureCoord(1.0f, 1.0f);
217  // Top left
218  manual_object_->position(0.0f, 0.0f, 0.0f);
219  manual_object_->textureCoord(0.0f, 0.0f);
220  // Top right
221  manual_object_->position(0.0f, -metric_width, 0.0f);
222  manual_object_->textureCoord(1.0f, 0.0f);
223  manual_object_->end();
224 
225  Ogre::DataStreamPtr pixel_stream;
226  pixel_stream.bind(new Ogre::MemoryDataStream(rgb.data(), rgb.size()));
227 
228  if (!texture_.isNull()) {
229  Ogre::TextureManager::getSingleton().remove(texture_->getHandle());
230  texture_.setNull();
231  }
232  const std::string texture_name =
233  kSubmapTexturePrefix + GetSubmapIdentifier(trajectory_id_, submap_index_);
234  texture_ = Ogre::TextureManager::getSingleton().loadRawData(
235  texture_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
236  pixel_stream, response_.width, response_.height, Ogre::PF_BYTE_RGB,
237  Ogre::TEX_TYPE_2D, 0);
238 
239  Ogre::Pass* const pass = material_->getTechnique(0)->getPass(0);
240  pass->setSceneBlending(Ogre::SBF_ONE, Ogre::SBF_ONE_MINUS_SOURCE_ALPHA);
241  Ogre::TextureUnitState* const texture_unit =
242  pass->getNumTextureUnitStates() > 0 ? pass->getTextureUnitState(0)
243  : pass->createTextureUnitState();
244 
245  texture_unit->setTextureName(texture_->getName());
246  texture_unit->setTextureFiltering(Ogre::TFO_NONE);
247 }
248 
250  const Eigen::Quaterniond quaternion(slice_pose_.rotation());
251  const Ogre::Quaternion slice_rotation(quaternion.w(), quaternion.x(),
252  quaternion.y(), quaternion.z());
253  const Ogre::Vector3 slice_translation(slice_pose_.translation().x(),
254  slice_pose_.translation().y(),
255  slice_pose_.translation().z());
256  scene_node_->setPosition(orientation_ * slice_translation + position_);
257  scene_node_->setOrientation(orientation_ * slice_rotation);
258 }
259 
260 float DrawableSubmap::UpdateAlpha(const float target_alpha) {
261  if (std::abs(target_alpha - current_alpha_) > kAlphaUpdateThreshold ||
262  target_alpha == 0.f || target_alpha == 1.f) {
263  current_alpha_ = target_alpha;
264  }
265  return current_alpha_;
266 }
267 
269  if (visibility_->getBool()) {
270  if (scene_node_->numAttachedObjects() == 0) {
271  scene_node_->attachObject(manual_object_);
272  }
273  } else {
274  if (scene_node_->numAttachedObjects() > 0) {
275  scene_node_->detachObject(manual_object_);
276  }
277  }
278 }
279 
280 } // namespace cartographer_rviz
double now()
Ogre::ManualObject * manual_object_
f
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
Ogre::SceneNode *const scene_node_
bool call(MReq &req, MRes &res)
std::unique_ptr<::rviz::BoolProperty > visibility_
::cartographer::common::Mutex mutex_
std::future< void > rpc_request_future_
void SetAlpha(double current_tracking_z)
void Update(const ::std_msgs::Header &header, const ::cartographer_ros_msgs::SubmapEntry &metadata,::rviz::FrameManager *frame_manager)
float UpdateAlpha(float target_alpha)
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
bool MaybeFetchTexture(ros::ServiceClient *client)
Ogre::SceneManager *const scene_manager_
Mutex::Locker MutexLocker
r
DrawableSubmap(int trajectory_id, int submap_index, Ogre::SceneManager *scene_manager,::rviz::Property *submap_category, const bool visible)


cartographer_rviz
Author(s):
autogenerated on Wed Jun 5 2019 22:36:03