ogre_slice.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/ogre_slice.h"
00018 
00019 #include <string>
00020 #include <vector>
00021 
00022 #include "OgreGpuProgramParams.h"
00023 #include "OgreImage.h"
00024 #include "OgreMaterialManager.h"
00025 #include "OgreTechnique.h"
00026 #include "OgreTextureManager.h"
00027 #include "absl/strings/str_cat.h"
00028 #include "cartographer/common/port.h"
00029 
00030 namespace cartographer_rviz {
00031 
00032 namespace {
00033 
00034 constexpr char kManualObjectPrefix[] = "ManualObjectSubmap";
00035 constexpr char kSubmapSourceMaterialName[] = "cartographer_ros/Submap";
00036 constexpr char kSubmapMaterialPrefix[] = "SubmapMaterial";
00037 constexpr char kSubmapTexturePrefix[] = "SubmapTexture";
00038 
00039 std::string GetSliceIdentifier(
00040     const ::cartographer::mapping::SubmapId& submap_id, const int slice_id) {
00041   return absl::StrCat(submap_id.trajectory_id, "-", submap_id.submap_index, "-",
00042                       slice_id);
00043 }
00044 
00045 }  // namespace
00046 
00047 Ogre::Vector3 ToOgre(const Eigen::Vector3d& v) {
00048   return Ogre::Vector3(v.x(), v.y(), v.z());
00049 }
00050 
00051 Ogre::Quaternion ToOgre(const Eigen::Quaterniond& q) {
00052   return Ogre::Quaternion(q.w(), q.x(), q.y(), q.z());
00053 }
00054 
00055 OgreSlice::OgreSlice(const ::cartographer::mapping::SubmapId& id, int slice_id,
00056                      Ogre::SceneManager* const scene_manager,
00057                      Ogre::SceneNode* const submap_node)
00058     : id_(id),
00059       slice_id_(slice_id),
00060       scene_manager_(scene_manager),
00061       submap_node_(submap_node),
00062       slice_node_(submap_node_->createChildSceneNode()),
00063       manual_object_(scene_manager_->createManualObject(absl::StrCat(
00064           kManualObjectPrefix, GetSliceIdentifier(id, slice_id)))) {
00065   material_ = Ogre::MaterialManager::getSingleton().getByName(
00066       kSubmapSourceMaterialName);
00067   material_ = material_->clone(
00068       absl::StrCat(kSubmapMaterialPrefix, GetSliceIdentifier(id_, slice_id_)));
00069   material_->setReceiveShadows(false);
00070   material_->getTechnique(0)->setLightingEnabled(false);
00071   material_->setCullingMode(Ogre::CULL_NONE);
00072   material_->setDepthBias(-1.f, 0.f);
00073   material_->setDepthWriteEnabled(false);
00074   slice_node_->attachObject(manual_object_);
00075 }
00076 
00077 OgreSlice::~OgreSlice() {
00078   Ogre::MaterialManager::getSingleton().remove(material_->getHandle());
00079   if (!texture_.isNull()) {
00080     Ogre::TextureManager::getSingleton().remove(texture_->getHandle());
00081     texture_.setNull();
00082   }
00083   scene_manager_->destroySceneNode(slice_node_);
00084   scene_manager_->destroyManualObject(manual_object_);
00085 }
00086 
00087 void OgreSlice::Update(
00088     const ::cartographer::io::SubmapTexture& submap_texture) {
00089   slice_node_->setPosition(ToOgre(submap_texture.slice_pose.translation()));
00090   slice_node_->setOrientation(ToOgre(submap_texture.slice_pose.rotation()));
00091   // The call to Ogre's loadRawData below does not work with an RG texture,
00092   // therefore we create an RGB one whose blue channel is always 0.
00093   std::vector<char> rgb;
00094   CHECK_EQ(submap_texture.pixels.intensity.size(),
00095            submap_texture.pixels.alpha.size());
00096   for (size_t i = 0; i < submap_texture.pixels.intensity.size(); ++i) {
00097     rgb.push_back(submap_texture.pixels.intensity[i]);
00098     rgb.push_back(submap_texture.pixels.alpha[i]);
00099     rgb.push_back(0);
00100   }
00101 
00102   manual_object_->clear();
00103   const float metric_width = submap_texture.resolution * submap_texture.width;
00104   const float metric_height = submap_texture.resolution * submap_texture.height;
00105   manual_object_->begin(material_->getName(),
00106                         Ogre::RenderOperation::OT_TRIANGLE_STRIP);
00107   // Bottom left
00108   manual_object_->position(-metric_height, 0.0f, 0.0f);
00109   manual_object_->textureCoord(0.0f, 1.0f);
00110   // Bottom right
00111   manual_object_->position(-metric_height, -metric_width, 0.0f);
00112   manual_object_->textureCoord(1.0f, 1.0f);
00113   // Top left
00114   manual_object_->position(0.0f, 0.0f, 0.0f);
00115   manual_object_->textureCoord(0.0f, 0.0f);
00116   // Top right
00117   manual_object_->position(0.0f, -metric_width, 0.0f);
00118   manual_object_->textureCoord(1.0f, 0.0f);
00119   manual_object_->end();
00120 
00121   Ogre::DataStreamPtr pixel_stream;
00122   pixel_stream.bind(new Ogre::MemoryDataStream(rgb.data(), rgb.size()));
00123 
00124   if (!texture_.isNull()) {
00125     Ogre::TextureManager::getSingleton().remove(texture_->getHandle());
00126     texture_.setNull();
00127   }
00128   const std::string texture_name =
00129       absl::StrCat(kSubmapTexturePrefix, GetSliceIdentifier(id_, slice_id_));
00130   texture_ = Ogre::TextureManager::getSingleton().loadRawData(
00131       texture_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00132       pixel_stream, submap_texture.width, submap_texture.height,
00133       Ogre::PF_BYTE_RGB, Ogre::TEX_TYPE_2D, 0);
00134 
00135   Ogre::Pass* const pass = material_->getTechnique(0)->getPass(0);
00136   pass->setSceneBlending(Ogre::SBF_ONE, Ogre::SBF_ONE_MINUS_SOURCE_ALPHA);
00137   Ogre::TextureUnitState* const texture_unit =
00138       pass->getNumTextureUnitStates() > 0 ? pass->getTextureUnitState(0)
00139                                           : pass->createTextureUnitState();
00140 
00141   texture_unit->setTextureName(texture_->getName());
00142   texture_unit->setTextureFiltering(Ogre::TFO_NONE);
00143 }
00144 
00145 void OgreSlice::SetAlpha(const float alpha) {
00146   const Ogre::GpuProgramParametersSharedPtr parameters =
00147       material_->getTechnique(0)->getPass(0)->getFragmentProgramParameters();
00148   parameters->setNamedConstant("u_alpha", alpha);
00149 }
00150 
00151 void OgreSlice::SetVisibility(bool visibility) { visibility_ = visibility; }
00152 
00153 void OgreSlice::UpdateOgreNodeVisibility(bool submap_visibility) {
00154   slice_node_->setVisible(submap_visibility && visibility_);
00155 }
00156 
00157 }  // namespace cartographer_rviz


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