target_visualizer_display.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 Willow Garage 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 #include <rviz/view_manager.h>
00036 #include <rviz/render_panel.h>
00037 #include <rviz/uniform_string_stream.h>
00038 #include <OGRE/OgreCamera.h>
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include "target_visualizer_display.h"
00041 #include <OGRE/OgreManualObject.h>
00042 
00043 namespace jsk_rviz_plugin
00044 {
00045   const float arrow_animation_duration = 1.0;
00046   const double minimum_font_size = 0.2;
00047   
00048   TargetVisualizerDisplay::TargetVisualizerDisplay():
00049     message_recieved_(false)
00050   {
00051     target_name_property_ = new rviz::StringProperty(
00052       "target name", "target",
00053       "name of the target",
00054       this, SLOT(updateTargetName())
00055       );
00056     radius_property_ = new rviz::FloatProperty(
00057       "radius", 1.0,
00058       "radius of the target mark",
00059       this, SLOT(updateRadius()));
00060     radius_property_->setMin(0.0);
00061     alpha_property_ = new rviz::FloatProperty(
00062       "alpha", 0.8,
00063       "0 is fully transparent, 1.0 is fully opaque.",
00064       this, SLOT(updateAlpha()));
00065     alpha_property_->setMin(0.0);
00066     alpha_property_->setMax(1.0);
00067     color_property_ = new rviz::ColorProperty(
00068       "color", QColor(25, 255, 240),
00069       "color of the target",
00070       this, SLOT(updateColor()));
00071     shape_type_property_ = new rviz::EnumProperty(
00072       "type", "Simple Circle",
00073       "Shape to display the pose as",
00074       this, SLOT(updateShapeType()));
00075     shape_type_property_->addOption("Simple Circle", SimpleCircle);
00076     shape_type_property_->addOption("Decoreted Circle", GISCircle);
00077   }
00078 
00079   TargetVisualizerDisplay::~TargetVisualizerDisplay()
00080   {
00081     delete target_name_property_;
00082     delete alpha_property_;
00083     delete color_property_;
00084     delete radius_property_;
00085   }
00086 
00087   void TargetVisualizerDisplay::onEnable()
00088   {
00089     subscribe();
00090     visualizer_->setEnable(false); // keep false, it will be true
00091                                    // in side of processMessae callback.
00092   }
00093   
00094   void TargetVisualizerDisplay::processMessage(
00095     const geometry_msgs::PoseStamped::ConstPtr& msg)
00096   {
00097     boost::mutex::scoped_lock lock(mutex_);
00098     message_recieved_ = true;
00099     visualizer_->setEnable(isEnabled());
00100     if (!isEnabled()) {
00101       return;
00102     }
00103     Ogre::Quaternion orientation;
00104     Ogre::Vector3 position;
00105     if(!context_->getFrameManager()->transform(msg->header,
00106                                                msg->pose,
00107                                                position, orientation))
00108     {
00109       ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00110                  msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00111       return;
00112     }
00113     visualizer_->setPosition(position);
00114   }
00115 
00116   
00117   void TargetVisualizerDisplay::update(float wall_dt, float ros_dt)
00118   {
00119     if (!message_recieved_) {
00120       return;
00121     }
00122     visualizer_->setOrientation(context_);
00123     visualizer_->update(wall_dt, ros_dt);
00124   }
00125 
00126   void TargetVisualizerDisplay::onInitialize()
00127   {
00128     MFDClass::onInitialize();
00129     scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00130     
00131     updateRadius();
00132     updateShapeType();
00133     // updateTargetName();
00134     // updateColor();
00135     // updateAlpha();
00136   }
00137 
00138   void TargetVisualizerDisplay::reset()
00139   {
00140     MFDClass::reset();
00141     message_recieved_ = false;
00142     visualizer_->setEnable(false);
00143   }
00144 
00145   void TargetVisualizerDisplay::updateTargetName()
00146   {
00147     boost::mutex::scoped_lock lock(mutex_);
00148     target_name_ = target_name_property_->getStdString();
00149     if (visualizer_) {
00150       visualizer_->setText(target_name_);
00151     }
00152   }
00153   
00154   void TargetVisualizerDisplay::updateRadius()
00155   {
00156     boost::mutex::scoped_lock lock(mutex_);
00157     radius_ = radius_property_->getFloat();
00158     if (visualizer_) {
00159       visualizer_->setSize(radius_);
00160     }
00161   }
00162 
00163   void TargetVisualizerDisplay::updateAlpha()
00164   {
00165     boost::mutex::scoped_lock lock(mutex_);
00166     alpha_ = alpha_property_->getFloat();
00167     if (visualizer_) {
00168       visualizer_->setAlpha(alpha_);
00169     }
00170   }
00171 
00172   void TargetVisualizerDisplay::updateColor()
00173   {
00174     boost::mutex::scoped_lock lock(mutex_);
00175     color_ = color_property_->getColor();
00176     if (visualizer_) {
00177       visualizer_->setColor(color_);
00178     }
00179   }
00180   
00181   void TargetVisualizerDisplay::updateShapeType()
00182   {
00183     if (current_type_ != shape_type_property_->getOptionInt()) {
00184       {
00185         boost::mutex::scoped_lock lock(mutex_);
00186         if (shape_type_property_->getOptionInt() == SimpleCircle) {
00187           current_type_ = SimpleCircle;
00188           // simple circle
00189           visualizer_.reset(new SimpleCircleFacingVisualizer(
00190                               scene_manager_,
00191                               scene_node_,
00192                               context_,
00193                               radius_));
00194         }
00195         else {
00196           current_type_ = GISCircle;
00197           // GIS
00198           GISCircleVisualizer* v = new GISCircleVisualizer(
00199             scene_manager_,
00200             scene_node_,
00201             radius_);
00202           v->setAnonymous(false);
00203           visualizer_.reset(v);
00204           
00205         }
00206       }
00207       updateTargetName();
00208       updateColor();
00209       updateAlpha();
00210     }
00211   }
00212 }
00213 
00214 #include <pluginlib/class_list_macros.h>
00215 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugin::TargetVisualizerDisplay, rviz::Display )
00216 


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44