25 #include "Eigen/Geometry" 26 #include "OgreGpuProgramParams.h" 27 #include "OgreImage.h" 30 #include "cartographer_ros_msgs/SubmapQuery.h" 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";
46 constexpr
double kFadeOutStartDistanceInMeters = 1.;
47 constexpr
double kFadeOutDistanceInMeters = 2.;
48 constexpr
float kAlphaUpdateThreshold = 0.2f;
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);
58 Ogre::SceneManager*
const scene_manager,
62 submap_index_(submap_index),
63 scene_manager_(scene_manager),
64 scene_node_(scene_manager->getRootSceneNode()->createChildSceneNode()),
65 manual_object_(scene_manager->createManualObject(
67 GetSubmapIdentifier(trajectory_id, submap_index))),
68 last_query_timestamp_(0) {
69 material_ = Ogre::MaterialManager::getSingleton().getByName(
70 kSubmapSourceMaterialName);
75 material_->getTechnique(0)->setLightingEnabled(
false);
76 material_->setCullingMode(Ogre::CULL_NONE);
83 visibility_ = ::cartographer::common::make_unique<::rviz::BoolProperty>(
84 "" , visible,
"" , submap_category,
96 Ogre::MaterialManager::getSingleton().remove(
material_->getHandle());
98 Ogre::TextureManager::getSingleton().remove(
texture_->getHandle());
106 const ::std_msgs::Header& header,
107 const ::cartographer_ros_msgs::SubmapEntry& metadata,
109 Ogre::Vector3 position;
110 Ogre::Quaternion orientation;
111 if (!frame_manager->
transform(header, metadata.pose, position, orientation)) {
116 position_ = position;
117 orientation_ = orientation;
128 QString(
"Toggle visibility of this individual submap.<br><br>" 129 "Trajectory %1, submap %2, submap version %3")
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;
148 last_query_timestamp_ = now;
150 ::cartographer_ros_msgs::SubmapQuery srv;
153 if (client->
call(srv)) {
157 response_ = srv.response;
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));
179 const Ogre::GpuProgramParametersSharedPtr parameters =
180 material_->getTechnique(0)->getPass(0)->getFragmentProgramParameters();
181 parameters->setNamedConstant(
"u_alpha",
UpdateAlpha(alpha));
187 std::string compressed_cells(response_.cells.begin(), response_.cells.end());
189 ::cartographer::common::FastGunzipString(compressed_cells, &cells);
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];
207 const float metric_width = response_.resolution * response_.width;
208 const float metric_height = response_.resolution * response_.height;
210 Ogre::RenderOperation::OT_TRIANGLE_STRIP);
225 Ogre::DataStreamPtr pixel_stream;
226 pixel_stream.bind(
new Ogre::MemoryDataStream(rgb.data(), rgb.size()));
229 Ogre::TextureManager::getSingleton().remove(
texture_->getHandle());
232 const std::string texture_name =
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);
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();
245 texture_unit->setTextureName(
texture_->getName());
246 texture_unit->setTextureFiltering(Ogre::TFO_NONE);
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);
261 if (std::abs(target_alpha -
current_alpha_) > kAlphaUpdateThreshold ||
262 target_alpha == 0.
f || target_alpha == 1.
f) {
Ogre::ManualObject * manual_object_
Ogre::TexturePtr texture_
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)
~DrawableSubmap() override
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_
Ogre::MaterialPtr material_
Mutex::Locker MutexLocker
DrawableSubmap(int trajectory_id, int submap_index, Ogre::SceneManager *scene_manager,::rviz::Property *submap_category, const bool visible)