textured_marker_plugin.cpp
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #include <mapviz_plugins/textured_marker_plugin.h>
00031 
00032 // C++ standard libraries
00033 #include <cmath>
00034 #include <cstdio>
00035 #include <vector>
00036 
00037 // Boost libraries
00038 #include <boost/algorithm/string.hpp>
00039 
00040 // QT libraries
00041 #include <QDialog>
00042 #include <QGLWidget>
00043 
00044 // ROS libraries
00045 #include <ros/master.h>
00046 #include <sensor_msgs/image_encodings.h>
00047 
00048 #include <swri_math_util/constants.h>
00049 
00050 #include <mapviz/select_topic_dialog.h>
00051 
00052 // Declare plugin
00053 #include <pluginlib/class_list_macros.h>
00054 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::TexturedMarkerPlugin, mapviz::MapvizPlugin)
00055 
00056 namespace mapviz_plugins
00057 {
00058   TexturedMarkerPlugin::TexturedMarkerPlugin() :
00059     config_widget_(new QWidget()),
00060     is_marker_array_(false)
00061   {
00062     ui_.setupUi(config_widget_);
00063 
00064     // Set background white
00065     QPalette p(config_widget_->palette());
00066     p.setColor(QPalette::Background, Qt::white);
00067     config_widget_->setPalette(p);
00068 
00069     // Set status text red
00070     QPalette p3(ui_.status->palette());
00071     p3.setColor(QPalette::Text, Qt::red);
00072     ui_.status->setPalette(p3);
00073 
00074     QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00075     QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00076 
00077     // By using a signal/slot connection, we ensure that we only generate GL textures on the
00078     // main thread in case a non-main thread handles the ROS callbacks.
00079     qRegisterMetaType<marti_visualization_msgs::TexturedMarkerConstPtr>("TexturedMarkerConstPtr");
00080     qRegisterMetaType<marti_visualization_msgs::TexturedMarkerArrayConstPtr>("TexturedMarkerArrayConstPtr");
00081 
00082     QObject::connect(this, 
00083                      SIGNAL(MarkerReceived(const marti_visualization_msgs::TexturedMarkerConstPtr)),
00084                      this,
00085                      SLOT(ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr)));
00086     QObject::connect(this,
00087                      SIGNAL(MarkersReceived(const marti_visualization_msgs::TexturedMarkerArrayConstPtr)),
00088                      this,
00089                      SLOT(ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr)));
00090   }
00091 
00092   TexturedMarkerPlugin::~TexturedMarkerPlugin()
00093   {
00094   }
00095 
00096   void TexturedMarkerPlugin::ClearHistory()
00097   {
00098     markers_.clear();
00099   }
00100 
00101   void TexturedMarkerPlugin::SelectTopic()
00102   {
00103     ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00104       "marti_visualization_msgs/TexturedMarker",
00105       "marti_visualization_msgs/TexturedMarkerArray");
00106 
00107     if (!topic.name.empty())
00108     {
00109       ui_.topic->setText(QString::fromStdString(topic.name));
00110 
00111       if (topic.datatype == "marti_visualization_msgs/TexturedMarkerArray")
00112       {
00113         is_marker_array_ = true;
00114       }
00115 
00116       TopicEdited();
00117     }
00118   }
00119 
00120   void TexturedMarkerPlugin::TopicEdited()
00121   {
00122     std::string topic = ui_.topic->text().trimmed().toStdString();
00123     if (topic != topic_)
00124     {
00125       initialized_ = false;
00126       markers_.clear();
00127       has_message_ = false;
00128       PrintWarning("No messages received.");
00129 
00130       marker_sub_.shutdown();
00131 
00132       topic_ = topic;
00133       if (!topic.empty())
00134       {
00135         if (is_marker_array_)
00136         {
00137           marker_sub_ = node_.subscribe(topic_, 1000, &TexturedMarkerPlugin::MarkerArrayCallback, this);
00138         }
00139         else
00140         {
00141           marker_sub_ = node_.subscribe(topic_, 1000, &TexturedMarkerPlugin::MarkerCallback, this);
00142         }
00143 
00144         ROS_INFO("Subscribing to %s", topic_.c_str());
00145       }
00146     }
00147   }
00148 
00149   void TexturedMarkerPlugin::ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
00150   {
00151     ProcessMarker(*marker);
00152   }
00153 
00154   void TexturedMarkerPlugin::ProcessMarker(const marti_visualization_msgs::TexturedMarker& marker)
00155   {
00156     if (!has_message_)
00157     {
00158       initialized_ = true;
00159       has_message_ = true;
00160     }
00161 
00162     // Note that unlike some plugins, this one does not store nor rely on the
00163     // source_frame_ member variable.  This one can potentially store many
00164     // messages with different source frames, so we need to store and transform
00165     // them individually.
00166 
00167     if (marker.action == marti_visualization_msgs::TexturedMarker::ADD)
00168     {
00169       MarkerData& markerData = markers_[marker.ns][marker.id];
00170       markerData.stamp = marker.header.stamp;
00171 
00172       markerData.transformed = true;
00173       markerData.alpha_ = marker.alpha;
00174       markerData.source_frame_ = marker.header.frame_id;
00175 
00176       swri_transform_util::Transform transform;
00177       if (!GetTransform(markerData.source_frame_, marker.header.stamp, transform))
00178       {
00179         markerData.transformed = false;
00180         PrintError("No transform between " + markerData.source_frame_ + " and " + target_frame_);
00181       }
00182 
00183       // Handle lifetime parameter
00184       ros::Duration lifetime = marker.lifetime;
00185       if (lifetime.isZero())
00186       {
00187         markerData.expire_time = ros::TIME_MAX;
00188       }
00189       else
00190       {
00191         // Temporarily add 5 seconds to fix some existing markers.
00192         markerData.expire_time = ros::Time::now() + lifetime + ros::Duration(5);
00193       }
00194 
00195       tf::Transform offset(
00196         tf::Quaternion(
00197           marker.pose.orientation.x,
00198           marker.pose.orientation.y,
00199           marker.pose.orientation.z,
00200           marker.pose.orientation.w), 
00201         tf::Vector3(
00202           marker.pose.position.x,
00203           marker.pose.position.y,
00204           marker.pose.position.z));
00205 
00206       double right = marker.image.width * marker.resolution / 2.0;
00207       double left = -right;
00208       double top = marker.image.height * marker.resolution / 2.0;
00209       double bottom = -top;
00210 
00211       tf::Vector3 top_left(left, top, 0);
00212       tf::Vector3 top_right(right, top, 0);
00213       tf::Vector3 bottom_left(left, bottom, 0);
00214       tf::Vector3 bottom_right(right, bottom, 0);
00215       
00216       top_left = offset * top_left;
00217       top_right = offset * top_right;
00218       bottom_left = offset * bottom_left;
00219       bottom_right = offset * bottom_right;
00220       
00221       markerData.quad_.clear();
00222       markerData.quad_.push_back(top_left);
00223       markerData.quad_.push_back(top_right);
00224       markerData.quad_.push_back(bottom_right);
00225       
00226       markerData.quad_.push_back(top_left);
00227       markerData.quad_.push_back(bottom_right);
00228       markerData.quad_.push_back(bottom_left);
00229       
00230       markerData.transformed_quad_.clear();
00231       for (size_t i = 0; i < markerData.quad_.size(); i++)
00232       {
00233         markerData.transformed_quad_.push_back(transform * markerData.quad_[i]);
00234       }
00235       
00236       int32_t max_dimension = std::max(marker.image.height, marker.image.width);
00237       int32_t new_size = 1;
00238       while (new_size < max_dimension)
00239         new_size = new_size << 1;
00240       
00241       if (new_size != markerData.texture_size_ || markerData.encoding_ != marker.image.encoding)
00242       {
00243         markerData.texture_size_ = new_size;
00244         
00245         markerData.encoding_ = marker.image.encoding;
00246         
00247         GLuint ids[1];
00248 
00249         //  Free the current texture.
00250         if (markerData.texture_id_ != -1)
00251         {
00252           ids[0] = static_cast<GLuint>(markerData.texture_id_);
00253           glDeleteTextures(1, &ids[0]);
00254         }
00255         
00256         // Get a new texture id.
00257         glGenTextures(1, &ids[0]);
00258         markerData.texture_id_ = ids[0];
00259 
00260         // Bind the texture with the correct size and null memory.
00261         glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.texture_id_));
00262 
00263         glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
00264 
00265         if (markerData.encoding_ == sensor_msgs::image_encodings::BGRA8)
00266         {
00267           markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_ * 4));
00268         }
00269         else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8)
00270         {
00271           markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_ * 3));
00272         }
00273         else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8)
00274         {
00275           markerData.texture_.resize(static_cast<size_t>(markerData.texture_size_ * markerData.texture_size_));
00276         }
00277         else
00278         {
00279           ROS_WARN("Unsupported encoding: %s", markerData.encoding_.c_str());
00280         }
00281 
00282         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
00283         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
00284 
00285         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
00286         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
00287 
00288         glTexEnvf( GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE );
00289 
00290         glBindTexture(GL_TEXTURE_2D, 0);
00291       }
00292       
00293       glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.texture_id_));
00294       
00295       if (markerData.encoding_ == sensor_msgs::image_encodings::BGRA8)
00296       {
00297         for (size_t row = 0; row < marker.image.height; row++)
00298         {
00299           for (size_t col = 0; col < marker.image.width; col++)
00300           {
00301             size_t src_index = (row * marker.image.width + col) * 4;
00302             size_t dst_index = (row * markerData.texture_size_ + col) * 4;
00303             
00304             markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0];
00305             markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1];
00306             markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2];
00307             markerData.texture_[dst_index + 3] = marker.image.data[src_index + 3];
00308           }
00309         }
00310       
00311         glTexImage2D(
00312             GL_TEXTURE_2D, 
00313             0, 
00314             GL_RGBA, 
00315             markerData.texture_size_, 
00316             markerData.texture_size_, 
00317             0, 
00318             GL_BGRA, 
00319             GL_UNSIGNED_BYTE, 
00320             markerData.texture_.data());
00321       }
00322       else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8)
00323       {
00324         for (size_t row = 0; row < marker.image.height; row++)
00325         {
00326           for (size_t col = 0; col < marker.image.width; col++)
00327           {
00328             size_t src_index = (row * marker.image.width + col) * 3;
00329             size_t dst_index = (row * markerData.texture_size_ + col) * 3;
00330             
00331             markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0];
00332             markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1];
00333             markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2];
00334           }
00335         }
00336       
00337         glTexImage2D(
00338             GL_TEXTURE_2D, 
00339             0, 
00340             GL_RGB, 
00341             markerData.texture_size_, 
00342             markerData.texture_size_, 
00343             0, 
00344             GL_BGR, 
00345             GL_UNSIGNED_BYTE, 
00346             markerData.texture_.data());
00347       }
00348       else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8)
00349       {
00350         for (size_t row = 0; row < marker.image.height; row++)
00351         {
00352           for (size_t col = 0; col < marker.image.width; col++)
00353           {
00354             size_t src_index = row * marker.image.width + col;
00355             size_t dst_index = row * markerData.texture_size_ + col;
00356             
00357             markerData.texture_[dst_index] = marker.image.data[src_index];
00358           }
00359         }
00360       
00361         glTexImage2D(
00362             GL_TEXTURE_2D, 
00363             0, 
00364             GL_LUMINANCE, 
00365             markerData.texture_size_, 
00366             markerData.texture_size_, 
00367             0, 
00368             GL_LUMINANCE, 
00369             GL_UNSIGNED_BYTE, 
00370             markerData.texture_.data());
00371       }
00372       
00373       glBindTexture(GL_TEXTURE_2D, 0);
00374       
00375       markerData.texture_x_ = static_cast<float>(marker.image.width) / static_cast<float>(markerData.texture_size_);
00376       markerData.texture_y_ = static_cast<float>(marker.image.height) / static_cast<float>(markerData.texture_size_);
00377     }
00378     else
00379     {
00380       markers_[marker.ns].erase(marker.id);
00381     }
00382   }
00383   
00384   void TexturedMarkerPlugin::ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
00385   {
00386     for (unsigned int i = 0; i < markers->markers.size(); i++)
00387     {
00388       ProcessMarker(markers->markers[i]);
00389     }
00390   }
00391   
00392 
00393   void TexturedMarkerPlugin::MarkerCallback(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
00394   {
00395     Q_EMIT MarkerReceived(marker);
00396   }
00397 
00398   void TexturedMarkerPlugin::MarkerArrayCallback(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
00399   {
00400     Q_EMIT MarkersReceived(markers);
00401   }
00402 
00403   void TexturedMarkerPlugin::PrintError(const std::string& message)
00404   {
00405     PrintErrorHelper(ui_.status, message);
00406   }
00407 
00408   void TexturedMarkerPlugin::PrintInfo(const std::string& message)
00409   {
00410     PrintInfoHelper(ui_.status, message);
00411   }
00412 
00413   void TexturedMarkerPlugin::PrintWarning(const std::string& message)
00414   {
00415     PrintWarningHelper(ui_.status, message);
00416   }
00417 
00418   QWidget* TexturedMarkerPlugin::GetConfigWidget(QWidget* parent)
00419   {
00420     config_widget_->setParent(parent);
00421 
00422     return config_widget_;
00423   }
00424 
00425   bool TexturedMarkerPlugin::Initialize(QGLWidget* canvas)
00426   {
00427     canvas_ = canvas;
00428 
00429     return true;
00430   }
00431 
00432   void TexturedMarkerPlugin::Draw(double x, double y, double scale)
00433   {
00434     ros::Time now = ros::Time::now();
00435 
00436     std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
00437     for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
00438     {
00439       std::map<int, MarkerData>::iterator markerIter;
00440       for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
00441       {
00442         MarkerData& marker = markerIter->second;
00443 
00444         if (marker.expire_time > now)
00445         {
00446           if (marker.transformed)
00447           {
00448             glEnable(GL_TEXTURE_2D);
00449 
00450             glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(marker.texture_id_));
00451           
00452             glBegin(GL_TRIANGLES);
00453             
00454             glColor4f(1.0f, 1.0f, 1.0f, marker.alpha_);
00455 
00456             double marker_x = marker.texture_x_;
00457             double marker_y = marker.texture_y_;
00458 
00459             glTexCoord2d(0, 0); glVertex2d(marker.transformed_quad_[0].x(), marker.transformed_quad_[0].y());
00460             glTexCoord2d(marker_x, 0); glVertex2d(marker.transformed_quad_[1].x(), marker.transformed_quad_[1].y());
00461             glTexCoord2d(marker_x, marker_y); glVertex2d(marker.transformed_quad_[2].x(), marker.transformed_quad_[2].y());
00462 
00463             glTexCoord2d(0, 0); glVertex2d(marker.transformed_quad_[3].x(), marker.transformed_quad_[3].y());
00464             glTexCoord2d(marker_x, marker_y); glVertex2d(marker.transformed_quad_[4].x(), marker.transformed_quad_[4].y());
00465             glTexCoord2d(0, marker_y); glVertex2d(marker.transformed_quad_[5].x(), marker.transformed_quad_[5].y());
00466 
00467             glEnd();
00468             
00469             glBindTexture(GL_TEXTURE_2D, 0);
00470 
00471             glDisable(GL_TEXTURE_2D);
00472             
00473             PrintInfo("OK");
00474           }
00475         }
00476       }
00477     }
00478   }
00479 
00480   void TexturedMarkerPlugin::Transform()
00481   {  
00482     std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
00483     for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter)
00484     {
00485       std::map<int, MarkerData>::iterator markerIter;
00486       for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
00487       {
00488         swri_transform_util::Transform transform;
00489         if (GetTransform(markerIter->second.source_frame_, markerIter->second.stamp, transform))
00490         {
00491           markerIter->second.transformed_quad_.clear();
00492           for (size_t i = 0; i < markerIter->second.quad_.size(); i++)
00493           {
00494             markerIter->second.transformed_quad_.push_back(transform * markerIter->second.quad_[i]);
00495           }
00496         }
00497       }
00498     }
00499   }
00500 
00501   void TexturedMarkerPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00502   {
00503     if (node["topic"])
00504     {
00505       std::string topic;
00506       node["topic"] >> topic;
00507       ui_.topic->setText(boost::trim_copy(topic).c_str());
00508     }
00509 
00510     if (node["is_marker_array"])
00511     {
00512       node["is_marker_array"] >> is_marker_array_;
00513     }
00514 
00515     TopicEdited();
00516   }
00517 
00518   void TexturedMarkerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00519   {
00520     emitter << YAML::Key << "topic" << YAML::Value << boost::trim_copy(ui_.topic->text().toStdString());
00521     emitter << YAML::Key << "is_marker_array" << YAML::Value << is_marker_array_;
00522   }
00523 }
00524 


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Jun 6 2019 18:51:07