facing_visualizer.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "facing_visualizer.h"
00037 #include <rviz/uniform_string_stream.h>
00038 #include <rviz/render_panel.h>
00039 #include <rviz/view_manager.h>
00040 #include <rviz/properties/parse_color.h>
00041 #include <QPainter>
00042 
00043 namespace jsk_rviz_plugins
00044 {
00045 
00046   const double minimum_font_size = 0.2;
00047   const float arrow_animation_duration = 1.0;
00048   
00049   SquareObject::SquareObject(Ogre::SceneManager* manager,
00050                              double outer_radius,
00051                              double inner_radius,
00052                              std::string name):
00053     manager_(manager), outer_radius_(outer_radius),
00054     inner_radius_(inner_radius), name_(name), polygon_type_(CIRCLE)
00055   {
00056     manual_ = manager->createManualObject();
00057     rebuildPolygon();
00058   }
00059 
00060   SquareObject::~SquareObject()
00061   {
00062     manual_->detachFromParent();
00063     manager_->destroyManualObject(manual_);
00064   }
00065 
00066   Ogre::ManualObject* SquareObject::getManualObject()
00067   {
00068     return manual_;
00069   }
00070 
00071   void SquareObject::setOuterRadius(double outer_radius)
00072   {
00073     outer_radius_ = outer_radius;
00074   }
00075 
00076   void SquareObject::setInnerRadius(double inner_radius)
00077   {
00078     inner_radius_ = inner_radius;
00079   }
00080 
00081   void SquareObject::rebuildPolygon()
00082   {
00083     manual_->clear();
00084     manual_->begin(name_,
00085                    Ogre::RenderOperation::OT_TRIANGLE_STRIP);
00086     if (polygon_type_ == CIRCLE) {
00087       const size_t resolution = 100;
00088       const double radius_ratio = inner_radius_ / outer_radius_;
00089       const double inner_offset = - outer_radius_ * 0.0;
00090       int counter = 0;
00091       for (size_t i = 0; i < resolution; i++) {
00092         double theta = 2.0 * M_PI / resolution * i;
00093         double next_theta = 2.0 * M_PI / resolution * (i + 1);
00094       
00095         manual_->position(inner_radius_ * cos(theta) + inner_offset,
00096                           inner_radius_ * sin(theta) + inner_offset,
00097                           0.0f);
00098         manual_->textureCoord((1 + radius_ratio *  cos(theta)) / 2.0,
00099                               (1.0 - radius_ratio * sin(theta)) / 2.0);
00100         manual_->index(counter++);
00101         manual_->position(outer_radius_ * cos(theta),
00102                           outer_radius_ * sin(theta),
00103                           0.0f);
00104         manual_->textureCoord((1 + cos(theta)) / 2.0,
00105                               (1.0 -sin(theta)) / 2.0);
00106         manual_->index(counter++);
00107         manual_->position(inner_radius_ * cos(next_theta) + inner_offset,
00108                           inner_radius_ * sin(next_theta) + inner_offset,
00109                           0.0f);
00110         manual_->textureCoord((1 + radius_ratio *  cos(next_theta)) / 2.0,
00111                               (1.0 - radius_ratio * sin(next_theta)) / 2.0);
00112         manual_->index(counter++);
00113         manual_->position(outer_radius_ * cos(next_theta),
00114                           outer_radius_ * sin(next_theta),
00115                           0.0f);
00116         manual_->textureCoord((1 + cos(next_theta)) / 2.0,
00117                               (1.0 -sin(next_theta)) / 2.0);
00118         manual_->index(counter++);
00119       
00120       }
00121     }
00122     else if (polygon_type_ == SQUARE) {
00123       manual_->position(outer_radius_, outer_radius_,
00124                         0.0f);     // 1
00125       manual_->textureCoord(0, 0); // 4
00126       manual_->index(0);
00127       
00128       manual_->position(-outer_radius_, outer_radius_,
00129                         0.0f);  // 2
00130       manual_->textureCoord(0, 1); // 3
00131       manual_->index(1);
00132       
00133       manual_->position(-outer_radius_, -outer_radius_,
00134                         0.0f);  // 3
00135       manual_->textureCoord(1, 1); // 2
00136       manual_->index(2);
00137       
00138       manual_->position(outer_radius_, -outer_radius_,
00139                         0.0f);  // 4
00140       manual_->textureCoord(1, 0); // 1
00141       manual_->index(3);
00142       
00143       manual_->position(outer_radius_, outer_radius_,
00144                         0.0f);  // 1
00145       manual_->textureCoord(0, 0); // 4
00146       manual_->index(4);
00147     }
00148     // for (size_t i = 0; i < resolution; i++) {
00149     // }
00150     // manual_->index(0);
00151     manual_->end();
00152   }
00153 
00154   void SquareObject::setPolygonType(PolygonType type)
00155   {
00156     polygon_type_ = type;
00157   }
00158   
00159   TextureObject::TextureObject(const int width, const int height,
00160                                const std::string name):
00161     width_(width), height_(height), name_(name)
00162   {
00163     texture_ = Ogre::TextureManager::getSingleton().createManual(
00164       name,
00165       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00166       Ogre::TEX_TYPE_2D,
00167        width, height,
00168       0,
00169       Ogre::PF_A8R8G8B8,
00170       Ogre::TU_DEFAULT
00171       );
00172     material_ = Ogre::MaterialManager::getSingleton().create(
00173       getMaterialName(), // name
00174       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00175  
00176     material_->getTechnique(0)->getPass(0)->createTextureUnitState(
00177       texture_->getName());
00178     material_->setReceiveShadows(false);
00179     material_->getTechnique(0)->setLightingEnabled(true);
00180     material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
00181     material_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
00182     material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
00183     material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
00184       
00185     material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
00186     material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_->getName());
00187     material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00188 
00189     material_->getTechnique(0)->getPass(0)
00190       ->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00191      // material_->getTechnique(0)->getPass(0)
00192      //   ->setSceneBlending(Ogre::SBT_MODULATE);
00193 
00194   }
00195 
00196   TextureObject::~TextureObject()
00197   {
00198     material_->unload();
00199     Ogre::MaterialManager::getSingleton().remove(material_->getName());
00200   }
00201   
00202   ScopedPixelBuffer TextureObject::getBuffer()
00203   {
00204     return ScopedPixelBuffer(texture_->getBuffer());
00205   }
00206 
00207   std::string TextureObject::getMaterialName()
00208   {
00209     return name_ + "Material";
00210   }
00211 
00212   FacingObject::FacingObject(Ogre::SceneManager* manager,
00213                              Ogre::SceneNode* parent,
00214                              double size):
00215     scene_manager_(manager), size_(size), enable_(true), text_("")
00216   {
00217     node_ = parent->createChildSceneNode();
00218   }
00219 
00220   FacingObject::~FacingObject()
00221   {
00222     node_->detachAllObjects();
00223     scene_manager_->destroySceneNode(node_);
00224   }
00225   
00226   void FacingObject::setPosition(Ogre::Vector3& pos)
00227   {
00228     node_->setPosition(pos);
00229   }
00230   
00231   void FacingObject::setOrientation(rviz::DisplayContext* context)
00232   {
00233     rviz::ViewManager* manager = context->getViewManager();
00234     rviz::RenderPanel* panel = manager->getRenderPanel();
00235     Ogre::Camera* camera = panel->getCamera();
00236     Ogre::Quaternion q = camera->getDerivedOrientation();
00237     setOrientation(q);
00238   }
00239 
00240   void FacingObject::setOrientation(Ogre::Quaternion& rot)
00241   {
00242     node_->setOrientation(rot);
00243   }
00244 
00245   void FacingObject::setSize(double size)
00246   {
00247     size_ = size;
00248   }
00249 
00250   void FacingObject::setEnable(bool enable)
00251   {
00252     enable_ = enable;
00253     node_->setVisible(enable_);
00254   }
00255 
00256   void FacingObject::setText(std::string text)
00257   {
00258     text_ = text;
00259     //updateTextUnderLine();
00260     updateText();
00261   }
00262 
00263   void FacingObject::setAlpha(double alpha)
00264   {
00265     color_.a = alpha;
00266     updateColor();
00267   }
00268 
00269   void FacingObject::setColor(QColor color)
00270   {
00271     color_.r = color.red() / 255.0;
00272     color_.g = color.green() / 255.0;
00273     color_.b = color.blue() / 255.0;
00274     updateColor();
00275   }
00276 
00277   void FacingObject::setColor(Ogre::ColourValue color)
00278   {
00279     color_ = color;
00280     updateColor();
00281   }
00282   
00283   SimpleCircleFacingVisualizer::SimpleCircleFacingVisualizer(
00284     Ogre::SceneManager* manager,
00285     Ogre::SceneNode* parent,
00286     rviz::DisplayContext* context,
00287     double size,
00288     std::string text):
00289     FacingObject(manager, parent, size)
00290   {
00291     line_ = new rviz::BillboardLine(
00292       context->getSceneManager(),
00293       node_);
00294     text_under_line_ = new rviz::BillboardLine(
00295       context->getSceneManager(),
00296       node_);
00297     target_text_node_ = node_->createChildSceneNode();
00298     msg_ = new rviz::MovableText("not initialized", "Arial", 0.05);
00299     msg_->setVisible(false);
00300     msg_->setTextAlignment(rviz::MovableText::H_LEFT,
00301                            rviz::MovableText::V_ABOVE);
00302     target_text_node_->attachObject(msg_);
00303     createArrows(context);
00304     updateLine();
00305     updateTextUnderLine();
00306     updateText();
00307     setEnable(false);
00308   }
00309 
00310   SimpleCircleFacingVisualizer::~SimpleCircleFacingVisualizer()
00311   {
00312     delete line_;
00313     delete text_under_line_;
00314     delete msg_;
00315     scene_manager_->destroyManualObject(upper_arrow_);
00316     scene_manager_->destroyManualObject(lower_arrow_);
00317     scene_manager_->destroyManualObject(left_arrow_);
00318     scene_manager_->destroyManualObject(right_arrow_);
00319     upper_material_->unload();
00320     lower_material_->unload();
00321     left_material_->unload();
00322     right_material_->unload();
00323     Ogre::MaterialManager::getSingleton().remove(upper_material_->getName());
00324     Ogre::MaterialManager::getSingleton().remove(lower_material_->getName());
00325     Ogre::MaterialManager::getSingleton().remove(left_material_->getName());
00326     Ogre::MaterialManager::getSingleton().remove(right_material_->getName());
00327   }
00328 
00329   void SimpleCircleFacingVisualizer::update(float wall_dt, float ros_dt)
00330   {
00331     double t_ = ros::WallTime::now().toSec();
00332     double t_rate
00333       = fmod(t_, arrow_animation_duration) / arrow_animation_duration;
00334     upper_arrow_node_->setPosition(0, (1.3 - 0.3 * t_rate) * size_, 0);
00335     lower_arrow_node_->setPosition(0, (-1.3 + 0.3 * t_rate) * size_, 0);
00336     left_arrow_node_->setPosition((1.3 - 0.3 * t_rate) * size_, 0, 0);
00337     right_arrow_node_->setPosition((-1.3 + 0.3 * t_rate) * size_, 0, 0);
00338   }
00339   
00340   void SimpleCircleFacingVisualizer::reset()
00341   {
00342     line_->clear();
00343     text_under_line_->clear();
00344     msg_->setVisible(false);
00345   }
00346 
00347   void SimpleCircleFacingVisualizer::updateArrowsObjects(Ogre::ColourValue color)
00348   {
00349     const double size_factor = 0.15;
00350     upper_arrow_node_->setPosition(Ogre::Vector3(0, size_ * 1.0, 0.0));
00351     upper_arrow_->clear();
00352     upper_arrow_->estimateVertexCount(3);
00353     upper_arrow_->begin(upper_material_name_,
00354                         Ogre::RenderOperation::OT_TRIANGLE_LIST);
00355     
00356     upper_arrow_->colour(color);
00357     upper_arrow_->position(Ogre::Vector3(0, size_ * size_factor, 0));
00358     upper_arrow_->colour(color);
00359     upper_arrow_->position(Ogre::Vector3(size_ * size_factor,
00360                                          size_ * size_factor * 2,
00361                                          0));
00362     upper_arrow_->colour(color);
00363     upper_arrow_->position(Ogre::Vector3(-size_ * size_factor,
00364                                          size_ * size_factor * 2,
00365                                          0));
00366     upper_arrow_->end();
00367     
00368     lower_arrow_node_->setPosition(Ogre::Vector3(0, -size_ * 1.0, 0.0));
00369     lower_arrow_->clear();
00370     lower_arrow_->estimateVertexCount(3);
00371     lower_arrow_->begin(lower_material_name_,
00372                         Ogre::RenderOperation::OT_TRIANGLE_LIST);
00373     
00374     lower_arrow_->colour(color);
00375     lower_arrow_->position(Ogre::Vector3(0,
00376                                          -size_ * size_factor,
00377                                          0));
00378     lower_arrow_->colour(color);
00379     lower_arrow_->position(Ogre::Vector3(size_ * size_factor,
00380                                          -size_ * size_factor * 2,
00381                                          0));
00382     lower_arrow_->colour(color);
00383     lower_arrow_->position(Ogre::Vector3(-size_ * size_factor,
00384                                          -size_ * size_factor * 2,
00385                                          0));
00386     lower_arrow_->end();
00387     left_arrow_node_->setPosition(Ogre::Vector3(size_ * 1.0, 0.0, 0.0));
00388     left_arrow_->clear();
00389     left_arrow_->estimateVertexCount(3);
00390     left_arrow_->begin(left_material_name_,
00391                        Ogre::RenderOperation::OT_TRIANGLE_LIST);
00392     
00393     left_arrow_->colour(color);
00394     left_arrow_->position(Ogre::Vector3(size_ * size_factor,
00395                                         0.0,
00396                                         0));
00397     left_arrow_->colour(color);
00398     left_arrow_->position(Ogre::Vector3(size_ * size_factor * 2,
00399                                         size_ * size_factor,
00400                                         0));
00401     left_arrow_->colour(color);
00402     left_arrow_->position(Ogre::Vector3(size_ * size_factor * 2,
00403                                         - size_ * size_factor,
00404                                         0));
00405     left_arrow_->end();
00406     
00407     right_arrow_node_->setPosition(Ogre::Vector3(-size_ * 1.0, 0.0, 0.0));
00408     right_arrow_->clear();
00409     right_arrow_->estimateVertexCount(3);
00410     right_arrow_->begin(right_material_name_,
00411                         Ogre::RenderOperation::OT_TRIANGLE_LIST);
00412     
00413     right_arrow_->colour(color);
00414     right_arrow_->position(Ogre::Vector3(-size_ * size_factor,
00415                                          0.0,
00416                                          0));
00417     right_arrow_->colour(color);
00418     right_arrow_->position(Ogre::Vector3(-size_ * size_factor * 2,
00419                                          size_ * size_factor,
00420                                          0));
00421     right_arrow_->colour(color);
00422     right_arrow_->position(Ogre::Vector3(-size_ * size_factor * 2,
00423                                          - size_ * size_factor,
00424                                          0));
00425     right_arrow_->end();
00426     
00427     
00428     upper_material_->getTechnique(0)->setLightingEnabled(false);
00429     upper_material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00430     upper_material_->getTechnique(0)->setDepthWriteEnabled( false );
00431     lower_material_->getTechnique(0)->setLightingEnabled(false);
00432     lower_material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00433     lower_material_->getTechnique(0)->setDepthWriteEnabled( false );
00434     left_material_->getTechnique(0)->setLightingEnabled(false);
00435     left_material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00436     left_material_->getTechnique(0)->setDepthWriteEnabled( false );
00437     right_material_->getTechnique(0)->setLightingEnabled(false);
00438     right_material_->getTechnique(0)->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00439     right_material_->getTechnique(0)->setDepthWriteEnabled( false );
00440   }
00441   
00442   // allocate material and node for arrrows
00443   void SimpleCircleFacingVisualizer::createArrows(
00444     rviz::DisplayContext* context)
00445   {
00446     static uint32_t count = 0;
00447     rviz::UniformStringStream ss;
00448     ss << "TargetVisualizerDisplayTriangle" << count++;
00449     ss << "Material";
00450     ss << "0";
00451     upper_material_name_ = std::string(ss.str());
00452     ss << "1";
00453     lower_material_name_ = std::string(ss.str());
00454     ss << "2";
00455     left_material_name_ = std::string(ss.str());
00456     ss << "3";
00457     right_material_name_ = std::string(ss.str());
00458     upper_material_ = Ogre::MaterialManager::getSingleton().create(
00459       upper_material_name_,
00460       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00461     lower_material_ = Ogre::MaterialManager::getSingleton().create(
00462       lower_material_name_,
00463       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00464     left_material_ = Ogre::MaterialManager::getSingleton().create(
00465       left_material_name_,
00466       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00467     right_material_ = Ogre::MaterialManager::getSingleton().create(
00468       right_material_name_,
00469       Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00470     
00471     upper_material_->setReceiveShadows(false);
00472     upper_material_->getTechnique(0)->setLightingEnabled(true);
00473     upper_material_->setCullingMode(Ogre::CULL_NONE);
00474     lower_material_->setReceiveShadows(false);
00475     lower_material_->getTechnique(0)->setLightingEnabled(true);
00476     lower_material_->setCullingMode(Ogre::CULL_NONE);
00477     left_material_->setReceiveShadows(false);
00478     left_material_->getTechnique(0)->setLightingEnabled(true);
00479     left_material_->setCullingMode(Ogre::CULL_NONE);
00480     right_material_->setReceiveShadows(false);
00481     right_material_->getTechnique(0)->setLightingEnabled(true);
00482     right_material_->setCullingMode(Ogre::CULL_NONE);
00483 
00484     upper_arrow_ = context->getSceneManager()->createManualObject(
00485       upper_material_name_);
00486     upper_arrow_node_ = node_->createChildSceneNode();
00487     upper_arrow_node_->attachObject(upper_arrow_);
00488     lower_arrow_ = context->getSceneManager()->createManualObject(
00489       lower_material_name_);
00490     lower_arrow_node_ = node_->createChildSceneNode();
00491     lower_arrow_node_->attachObject(lower_arrow_);
00492     left_arrow_ = context->getSceneManager()->createManualObject(
00493       left_material_name_);
00494     left_arrow_node_ = node_->createChildSceneNode();
00495     left_arrow_node_->attachObject(left_arrow_);
00496     right_arrow_ = context->getSceneManager()->createManualObject(
00497       right_material_name_);
00498     right_arrow_node_ = node_->createChildSceneNode();
00499     right_arrow_node_->attachObject(right_arrow_);
00500     updateArrowsObjects(color_);
00501   }
00502 
00503   void SimpleCircleFacingVisualizer::updateLine()
00504   {
00505     const int resolution = 100;
00506     line_->clear();
00507     line_->setColor(color_.r, color_.g, color_.b, color_.a);
00508     line_->setLineWidth(0.1 * size_);
00509     line_->setNumLines(1);
00510     line_->setMaxPointsPerLine(1024);
00511     for (size_t i = 0; i < resolution + 1; i++) {
00512       double x = size_ * cos(i * 2 * M_PI / resolution);
00513       double y = size_ * sin(i * 2 * M_PI / resolution);
00514       double z = 0;
00515       Ogre::Vector3 p;
00516       p[0] = x;
00517       p[1] = y;
00518       p[2] = z;
00519       line_->addPoint(p);
00520     }
00521   }
00522   
00523   // need msg to be initialized beforehand
00524   void SimpleCircleFacingVisualizer::updateTextUnderLine()
00525   {
00526     Ogre::Vector3 text_position(size_ * cos(45.0 / 180.0 * M_PI)
00527                                 + size_ / 2.0,
00528                                 size_ * sin(45.0 / 180.0 * M_PI)
00529                                 + size_ / 2.0,
00530                                 0);
00531     target_text_node_->setPosition(text_position);
00532     Ogre::Vector3 msg_size = msg_->GetAABB().getSize();
00533     text_under_line_->clear();
00534     text_under_line_->setColor(color_.r, color_.g, color_.b, color_.a);
00535     
00536     text_under_line_->setLineWidth(0.01);
00537     text_under_line_->setNumLines(1);
00538     text_under_line_->setMaxPointsPerLine(1024);
00539     Ogre::Vector3 A(size_ * cos(45.0 / 180.0 * M_PI),
00540                     size_ * sin(45.0 / 180.0 * M_PI),
00541                     0);
00542     Ogre::Vector3 B(text_position + Ogre::Vector3(- size_ / 4.0, 0, 0));
00543     Ogre::Vector3 C(text_position + Ogre::Vector3(msg_size[0], 0, 0));
00544     text_under_line_->addPoint(A);
00545     text_under_line_->addPoint(B);
00546     text_under_line_->addPoint(C);
00547   }
00548 
00549   void SimpleCircleFacingVisualizer::setSize(double size)
00550   {
00551     FacingObject::setSize(size);
00552     updateLine();
00553     updateText();
00554     updateTextUnderLine();
00555   }
00556 
00557   void SimpleCircleFacingVisualizer::setEnable(bool enable)
00558   {
00559     FacingObject::setEnable(enable);
00560     msg_->setVisible(enable);
00561     line_->getSceneNode()->setVisible(enable);
00562     text_under_line_->getSceneNode()->setVisible(enable);
00563   }
00564   
00565   void SimpleCircleFacingVisualizer::updateText()
00566   {
00567     msg_->setCaption(text_);
00568     msg_->setCharacterHeight(std::max(0.2 * size_, minimum_font_size));
00569   }
00570 
00571   void SimpleCircleFacingVisualizer::setText(std::string text)
00572   {
00573     text_ = text;
00574     updateTextUnderLine();
00575     updateText();
00576   }
00577 
00578   void SimpleCircleFacingVisualizer::updateColor()
00579   {
00580     msg_->setColor(color_);
00581     line_->setColor(color_.r, color_.g, color_.b, color_.a);
00582     text_under_line_->setColor(color_.r, color_.g, color_.b, color_.a);
00583     updateArrowsObjects(color_);
00584   }
00585   
00586   FacingTexturedObject::FacingTexturedObject(Ogre::SceneManager* manager,
00587                                              Ogre::SceneNode* parent,
00588                                              double size):
00589     FacingObject(manager, parent, size)
00590   {
00591     rviz::UniformStringStream ss;
00592     static int count = 0;
00593     ss << "FacingVisualizer" << count++;
00594     texture_object_.reset(new TextureObject(128, 128, ss.str()));
00595     square_object_.reset(new SquareObject(manager, size, 0,
00596                                           texture_object_->getMaterialName()));
00597     node_->attachObject(square_object_->getManualObject());
00598   }
00599   
00600 
00601   void FacingTexturedObject::setSize(double size)
00602   {
00603     FacingObject::setSize(size);
00604     square_object_->setOuterRadius(size_);
00605     square_object_->rebuildPolygon();
00606   }
00607 
00608   GISCircleVisualizer::GISCircleVisualizer(Ogre::SceneManager* manager,
00609                                            Ogre::SceneNode* parent,
00610                                            double size,
00611                                            std::string text):
00612     FacingTexturedObject(manager, parent, size), text_(text)
00613   {
00614 
00615   }
00616   
00617   void GISCircleVisualizer::update(float wall_dt, float ros_dt)
00618   {
00619     ros::WallTime now = ros::WallTime::now();
00620     std::string text = text_ + " ";
00621     {
00622       ScopedPixelBuffer buffer = texture_object_->getBuffer();
00623       QColor transparent(0, 0, 0, 0);
00624       QColor foreground = rviz::ogreToQt(color_);
00625       QColor white(255, 255, 255, color_.a * 255);
00626       QImage Hud = buffer.getQImage(128, 128, transparent);
00627       double line_width = 5;
00628       double inner_line_width = 10;
00629       double l = 128;
00630       //double cx = l / 2 - line_width / 4.0;
00631       double cx = l / 2;
00632       //double cy = l / 2 - line_width / 4.0;
00633       double cy = l / 2;
00634       double r = 48;
00635       double inner_r = 40;
00636       double mouse_r = 30;
00637       double mouse_cy_offset = 5;
00638       
00639       QPainter painter( &Hud );
00640       painter.setRenderHint(QPainter::Antialiasing, true);
00641       painter.setPen(QPen(foreground, line_width, Qt::SolidLine));
00642       painter.setBrush(white);
00643       painter.drawEllipse(line_width / 2.0, line_width / 2.0,
00644                           l - line_width, l - line_width);
00645       double offset_rate = fmod(now.toSec(), 10) / 10.0;
00646       double theta_offset = offset_rate * M_PI * 2.0;
00647       for (size_t ci = 0; ci < text.length(); ci++) {
00648         double theta = M_PI * 2.0 / text.length() * ci + theta_offset;
00649         painter.save();
00650         QFont font("DejaVu Sans Mono");
00651         font.setPointSize(10);
00652         font.setBold(true);
00653         painter.setFont(font);
00654         painter.translate(cx + r * cos(theta),
00655                           cy + r * sin(theta));
00656         painter.rotate(theta / M_PI * 180 + 90);
00657         painter.drawText(0, 0, text.substr(ci, 1).c_str());
00658         painter.restore();
00659       }
00660       painter.setPen(QPen(foreground, inner_line_width, Qt::SolidLine));
00661       painter.setBrush(transparent);
00662       painter.drawEllipse(cx - inner_r, cy - inner_r,
00663                           inner_r * 2, inner_r * 2);
00664       double mouse_c_x = cx;
00665       double mouse_c_y = cy - mouse_cy_offset;
00666       double start_angle = -25 * M_PI / 180;
00667       double end_angle = -125 * M_PI / 180;
00668       painter.setPen(QPen(foreground, line_width, Qt::SolidLine));
00669       painter.drawChord(mouse_c_x - mouse_r, mouse_c_y - mouse_r,
00670                         2.0 * mouse_r, 2.0 * mouse_r,
00671                         start_angle * 180 / M_PI * 16,
00672                         end_angle * 180 / M_PI * 16);
00673       painter.end();
00674     }
00675   }
00676 
00677   void GISCircleVisualizer::setAnonymous(bool anonymous)
00678   {
00679     anonymous_ = anonymous;
00680     if (!anonymous_) {
00681       square_object_->setInnerRadius(size_ * 0.6);
00682     }
00683     else {
00684       square_object_->setInnerRadius(0.0);
00685       
00686     }
00687     square_object_->rebuildPolygon();
00688   }
00689 
00690   void GISCircleVisualizer::setSize(double size)
00691   {
00692     FacingObject::setSize(size);
00693     square_object_->setOuterRadius(size_);
00694     if (!anonymous_) {
00695       square_object_->setInnerRadius(size_ * 0.6);
00696     }
00697     else {
00698       square_object_->setInnerRadius(0.0);
00699     }
00700     square_object_->rebuildPolygon();
00701   }
00702 
00703   
00704 }


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sun Sep 13 2015 22:29:03