drawable_submap.cc
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 #include "cartographer_rviz/drawable_submap.h"
00018 
00019 #include <chrono>
00020 #include <future>
00021 #include <sstream>
00022 #include <string>
00023 
00024 #include "Eigen/Core"
00025 #include "Eigen/Geometry"
00026 #include "absl/memory/memory.h"
00027 #include "cartographer/common/port.h"
00028 #include "cartographer_ros/msg_conversion.h"
00029 #include "cartographer_ros_msgs/SubmapQuery.h"
00030 #include "eigen_conversions/eigen_msg.h"
00031 #include "ros/ros.h"
00032 
00033 namespace cartographer_rviz {
00034 
00035 namespace {
00036 
00037 constexpr std::chrono::milliseconds kMinQueryDelayInMs(250);
00038 constexpr float kAlphaUpdateThreshold = 0.2f;
00039 
00040 const Ogre::ColourValue kSubmapIdColor(Ogre::ColourValue::Red);
00041 const Eigen::Vector3d kSubmapIdPosition(0.0, 0.0, 0.3);
00042 constexpr float kSubmapIdCharHeight = 0.2f;
00043 constexpr int kNumberOfSlicesPerSubmap = 2;
00044 
00045 }  // namespace
00046 
00047 DrawableSubmap::DrawableSubmap(const ::cartographer::mapping::SubmapId& id,
00048                                ::rviz::DisplayContext* const display_context,
00049                                Ogre::SceneNode* const map_node,
00050                                ::rviz::Property* const submap_category,
00051                                const bool visible, const bool pose_axes_visible,
00052                                const float pose_axes_length,
00053                                const float pose_axes_radius)
00054     : id_(id),
00055       display_context_(display_context),
00056       submap_node_(map_node->createChildSceneNode()),
00057       submap_id_text_node_(submap_node_->createChildSceneNode()),
00058       pose_axes_(display_context->getSceneManager(), submap_node_,
00059                  pose_axes_length, pose_axes_radius),
00060       pose_axes_visible_(pose_axes_visible),
00061       submap_id_text_(QString("(%1,%2)")
00062                           .arg(id.trajectory_id)
00063                           .arg(id.submap_index)
00064                           .toStdString()),
00065       last_query_timestamp_(0) {
00066   for (int slice_index = 0; slice_index < kNumberOfSlicesPerSubmap;
00067        ++slice_index) {
00068     ogre_slices_.emplace_back(absl::make_unique<OgreSlice>(
00069         id, slice_index, display_context->getSceneManager(), submap_node_));
00070   }
00071   // DrawableSubmap creates and manages its visibility property object
00072   // (a unique_ptr is needed because the Qt parent of the visibility
00073   // property is the submap_category object - the BoolProperty needs
00074   // to be destroyed along with the DrawableSubmap)
00075   visibility_ = absl::make_unique<::rviz::BoolProperty>(
00076       "" /* title */, visible, "" /* description */, submap_category,
00077       SLOT(ToggleVisibility()), this);
00078   submap_id_text_.setCharacterHeight(kSubmapIdCharHeight);
00079   submap_id_text_.setColor(kSubmapIdColor);
00080   submap_id_text_.setTextAlignment(::rviz::MovableText::H_CENTER,
00081                                    ::rviz::MovableText::V_ABOVE);
00082   submap_id_text_node_->setPosition(ToOgre(kSubmapIdPosition));
00083   submap_id_text_node_->attachObject(&submap_id_text_);
00084   TogglePoseMarkerVisibility();
00085   connect(this, SIGNAL(RequestSucceeded()), this, SLOT(UpdateSceneNode()));
00086 }
00087 
00088 DrawableSubmap::~DrawableSubmap() {
00089   // 'query_in_progress_' must be true until the Q_EMIT has happened. Qt then
00090   // makes sure that 'RequestSucceeded' is not called after our destruction.
00091   if (QueryInProgress()) {
00092     rpc_request_future_.wait();
00093   }
00094   display_context_->getSceneManager()->destroySceneNode(submap_node_);
00095   display_context_->getSceneManager()->destroySceneNode(submap_id_text_node_);
00096 }
00097 
00098 void DrawableSubmap::Update(
00099     const ::std_msgs::Header& header,
00100     const ::cartographer_ros_msgs::SubmapEntry& metadata) {
00101   absl::MutexLock locker(&mutex_);
00102   metadata_version_ = metadata.submap_version;
00103   pose_ = ::cartographer_ros::ToRigid3d(metadata.pose);
00104   submap_node_->setPosition(ToOgre(pose_.translation()));
00105   submap_node_->setOrientation(ToOgre(pose_.rotation()));
00106   display_context_->queueRender();
00107   visibility_->setName(
00108       QString("%1.%2").arg(id_.submap_index).arg(metadata_version_));
00109   visibility_->setDescription(
00110       QString("Toggle visibility of this individual submap.<br><br>"
00111               "Trajectory %1, submap %2, submap version %3")
00112           .arg(id_.trajectory_id)
00113           .arg(id_.submap_index)
00114           .arg(metadata_version_));
00115 }
00116 
00117 bool DrawableSubmap::MaybeFetchTexture(ros::ServiceClient* const client) {
00118   absl::MutexLock locker(&mutex_);
00119   // Received metadata version can also be lower if we restarted Cartographer.
00120   const bool newer_version_available =
00121       submap_textures_ == nullptr ||
00122       submap_textures_->version != metadata_version_;
00123   const std::chrono::milliseconds now =
00124       std::chrono::duration_cast<std::chrono::milliseconds>(
00125           std::chrono::system_clock::now().time_since_epoch());
00126   const bool recently_queried =
00127       last_query_timestamp_ + kMinQueryDelayInMs > now;
00128   if (!newer_version_available || recently_queried || query_in_progress_) {
00129     return false;
00130   }
00131   query_in_progress_ = true;
00132   last_query_timestamp_ = now;
00133   rpc_request_future_ = std::async(std::launch::async, [this, client]() {
00134     std::unique_ptr<::cartographer::io::SubmapTextures> submap_textures =
00135         ::cartographer_ros::FetchSubmapTextures(id_, client);
00136     absl::MutexLock locker(&mutex_);
00137     query_in_progress_ = false;
00138     if (submap_textures != nullptr) {
00139       // We emit a signal to update in the right thread, and pass via the
00140       // 'submap_texture_' member to simplify the signal-slot connection
00141       // slightly.
00142       submap_textures_ = std::move(submap_textures);
00143       Q_EMIT RequestSucceeded();
00144     }
00145   });
00146   return true;
00147 }
00148 
00149 bool DrawableSubmap::QueryInProgress() {
00150   absl::MutexLock locker(&mutex_);
00151   return query_in_progress_;
00152 }
00153 
00154 void DrawableSubmap::SetAlpha(const double current_tracking_z,
00155                               const float fade_out_start_distance_in_meters) {
00156   const float fade_out_distance_in_meters =
00157       2.f * fade_out_start_distance_in_meters;
00158   const double distance_z =
00159       std::abs(pose_.translation().z() - current_tracking_z);
00160   const double fade_distance =
00161       std::max(distance_z - fade_out_start_distance_in_meters, 0.);
00162   const float target_alpha = static_cast<float>(
00163       std::max(0., 1. - fade_distance / fade_out_distance_in_meters));
00164 
00165   if (std::abs(target_alpha - current_alpha_) > kAlphaUpdateThreshold ||
00166       target_alpha == 0.f || target_alpha == 1.f) {
00167     current_alpha_ = target_alpha;
00168   }
00169   for (auto& slice : ogre_slices_) {
00170     slice->SetAlpha(current_alpha_);
00171   }
00172   display_context_->queueRender();
00173 }
00174 
00175 void DrawableSubmap::SetSliceVisibility(size_t slice_index, bool visible) {
00176   ogre_slices_.at(slice_index)->SetVisibility(visible);
00177   ToggleVisibility();
00178 }
00179 
00180 void DrawableSubmap::UpdateSceneNode() {
00181   absl::MutexLock locker(&mutex_);
00182   for (size_t slice_index = 0; slice_index < ogre_slices_.size() &&
00183                                slice_index < submap_textures_->textures.size();
00184        ++slice_index) {
00185     ogre_slices_[slice_index]->Update(submap_textures_->textures[slice_index]);
00186   }
00187   display_context_->queueRender();
00188 }
00189 
00190 void DrawableSubmap::ToggleVisibility() {
00191   for (auto& ogre_slice : ogre_slices_) {
00192     ogre_slice->UpdateOgreNodeVisibility(visibility_->getBool());
00193   }
00194   display_context_->queueRender();
00195 }
00196 
00197 void DrawableSubmap::TogglePoseMarkerVisibility() {
00198   submap_id_text_node_->setVisible(pose_axes_visible_);
00199   pose_axes_.getSceneNode()->setVisible(pose_axes_visible_);
00200 }
00201 
00202 }  // namespace cartographer_rviz


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