footstep_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 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 "footstep_display.h"
00037 #include <rviz/validate_floats.h>
00038 #include <jsk_topic_tools/color_utils.h>
00039 
00040 namespace jsk_rviz_plugins
00041 {
00042   FootstepDisplay::FootstepDisplay()
00043   {
00044     alpha_property_ =  new rviz::FloatProperty( "Alpha", 0.5,
00045                                                 "0 is fully transparent, 1.0 is fully opaque.",
00046                                                 this, SLOT( updateAlpha() ));
00047     show_name_property_ = new rviz::BoolProperty(
00048       "Show Name", true,
00049       "Show name of each footstep",
00050       this, SLOT(updateShowName()));
00051     use_group_coloring_property_ = new rviz::BoolProperty(
00052       "Use Group Coloring", false,
00053       "Use footstep_group field to colorize footsteps",
00054       this, SLOT(updateUseGroupColoring()));
00055     width_property_ =  new rviz::FloatProperty(
00056       "Width", 0.15,
00057       "width of the footstep, it's not used if the dimensions is specified in Footstep message.",
00058       this, SLOT( updateWidth() ));
00059     height_property_ =  new rviz::FloatProperty(
00060       "height", 0.01,
00061       "height of the footstep, it's not used if the dimensions is specified in Footstep message.",
00062       this, SLOT( updateHeight() ));
00063 
00064     depth_property_ =  new rviz::FloatProperty(
00065       "depth", 0.3,
00066       "depth of the footstep, it's not used if the dimensions is specified in Footstep message.",
00067       this, SLOT( updateDepth() ));
00068   }
00069 
00070   FootstepDisplay::~FootstepDisplay()
00071   {
00072     delete alpha_property_;
00073     delete width_property_;
00074     delete height_property_;
00075     delete depth_property_;
00076     delete show_name_property_;
00077     delete use_group_coloring_property_;
00078     delete line_;
00079     // remove all the nodes
00080     for (size_t i = 0; i < text_nodes_.size(); i++) {
00081       Ogre::SceneNode* node = text_nodes_[i];
00082       node->removeAndDestroyAllChildren();
00083       node->detachAllObjects();
00084       scene_manager_->destroySceneNode(node);
00085     }
00086   }
00087 
00088   void FootstepDisplay::updateWidth()
00089   {
00090     width_ = width_property_->getFloat();
00091   }
00092 
00093   void FootstepDisplay::updateHeight()
00094   {
00095     height_ = height_property_->getFloat();
00096   }
00097 
00098   void FootstepDisplay::updateDepth()
00099   {
00100     depth_ = depth_property_->getFloat();
00101   }
00102   
00103   void FootstepDisplay::updateAlpha()
00104   {
00105     alpha_ = alpha_property_->getFloat();
00106   }
00107 
00108   void FootstepDisplay::updateShowName()
00109   {
00110     show_name_ = show_name_property_->getBool();
00111   }
00112 
00113   void FootstepDisplay::updateUseGroupColoring()
00114   {
00115     use_group_coloring_ = use_group_coloring_property_->getBool();
00116   }
00117   
00118   
00119   void FootstepDisplay::reset()
00120   {
00121     MFDClass::reset();
00122     shapes_.clear();
00123     line_->clear();
00124     allocateTexts(0);
00125   }
00126 
00127   bool FootstepDisplay::validateFloats( const jsk_footstep_msgs::FootstepArray& msg )
00128   {
00129     for (std::vector<jsk_footstep_msgs::Footstep>::const_iterator it = msg.footsteps.begin();
00130          it != msg.footsteps.end();
00131          ++it) {
00132       if (!rviz::validateFloats((*it).pose.position.x)
00133           || !rviz::validateFloats((*it).pose.position.y)
00134           || !rviz::validateFloats((*it).pose.position.z)
00135           || !rviz::validateFloats((*it).pose.orientation.x)
00136           || !rviz::validateFloats((*it).pose.orientation.y)
00137           || !rviz::validateFloats((*it).pose.orientation.z)
00138           || !rviz::validateFloats((*it).pose.orientation.w)
00139         ) {
00140         return false;
00141       }
00142     }
00143     return true;
00144   }
00145 
00146   void FootstepDisplay::onInitialize()
00147   {
00148     MFDClass::onInitialize();
00149     scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00150     line_ = new rviz::BillboardLine(context_->getSceneManager(), scene_node_);
00151     updateShowName();
00152     updateWidth();
00153     updateHeight();
00154     updateDepth();
00155     updateAlpha();
00156     updateUseGroupColoring();
00157   }
00158 
00159   void FootstepDisplay::allocateCubes(size_t num) {
00160     if (num > shapes_.size()) {
00161       // need to allocate
00162       for (size_t i = shapes_.size(); i < num; i++) {
00163         ShapePtr shape;
00164         shape.reset(new rviz::Shape(rviz::Shape::Cube, context_->getSceneManager(),
00165                                     scene_node_));
00166         shapes_.push_back(shape);
00167       }
00168     }
00169     else if (num < shapes_.size()) {
00170       // need to remove
00171       shapes_.resize(num);
00172     }
00173   }
00174 
00175   void FootstepDisplay::allocateTexts(size_t num) {
00176     if (num > texts_.size()) {
00177       // need to allocate
00178       for (size_t i = texts_.size(); i < num; i++) {
00179         // create nodes
00180         Ogre::SceneNode* node = scene_node_->createChildSceneNode();
00181         rviz::MovableText* text 
00182           = new rviz::MovableText("not initialized", "Arial", 0.05);
00183         text->setVisible(false);
00184         text->setTextAlignment(rviz::MovableText::H_CENTER,
00185                                rviz::MovableText::V_ABOVE);
00186         node->attachObject(text);
00187         texts_.push_back(text);
00188         text_nodes_.push_back(node);
00189       }
00190     }
00191     else if (num < texts_.size()) {
00192       for (int i = texts_.size() - 1; i >= (int)num; i--) {
00193         Ogre::SceneNode* node = text_nodes_[i];
00194         node->detachAllObjects();
00195         node->removeAndDestroyAllChildren();
00196         scene_manager_->destroySceneNode(node);
00197       }
00198       text_nodes_.resize(num);
00199       texts_.resize(num);
00200       
00201     }
00202   }
00203 
00204   double FootstepDisplay::minNotZero(double a, double b) {
00205     if (a == 0.0) {
00206       return b;
00207     }
00208     else if (b == 0.0) {
00209       return a;
00210     }
00211     else {
00212       return std::min(a, b);
00213     }
00214   }
00215 
00216   void FootstepDisplay::update(float wall_dt, float ros_dt)
00217   {
00218     for (size_t i = 0; i < shapes_.size(); i++) {
00219       ShapePtr shape = shapes_[i];
00220       texts_[i]->setVisible(show_name_); // TODO
00221       jsk_footstep_msgs::Footstep footstep = latest_footstep_->footsteps[i];
00222             // color
00223       if (use_group_coloring_) {
00224         std_msgs::ColorRGBA color
00225           = jsk_topic_tools::colorCategory20(footstep.footstep_group);
00226         shape->setColor(color.r, color.g, color.b, alpha_);
00227       }
00228       else {
00229         if (footstep.leg == jsk_footstep_msgs::Footstep::LEFT) {
00230           shape->setColor(0, 1, 0, alpha_);
00231         }
00232         else if (footstep.leg == jsk_footstep_msgs::Footstep::RIGHT) {
00233           shape->setColor(1, 0, 0, alpha_);
00234         }
00235         else {
00236           shape->setColor(1, 1, 1, alpha_);
00237         }
00238       }
00239 
00240     }
00241   }
00242   
00243   double FootstepDisplay::estimateTextSize(
00244     const jsk_footstep_msgs::Footstep& footstep)
00245   {
00246     if (footstep.dimensions.x == 0 &&
00247         footstep.dimensions.y == 0 &&
00248         footstep.dimensions.z == 0) {
00249       return std::max(minNotZero(minNotZero(footstep.dimensions.x,
00250                                             footstep.dimensions.y),
00251                                  footstep.dimensions.z),
00252                       0.1);
00253     }
00254     else {
00255       return std::max(minNotZero(minNotZero(depth_property_->getFloat(),
00256                                             width_property_->getFloat()),
00257                                  height_property_->getFloat()),
00258                       0.1);
00259         
00260     }
00261   }
00262   
00263   
00264   void FootstepDisplay::processMessage(const jsk_footstep_msgs::FootstepArray::ConstPtr& msg)
00265   {
00266     if (!validateFloats(*msg)) {
00267       setStatus(rviz::StatusProperty::Error, "Topic", "message contained invalid floating point values (nans or infs)");
00268       return;
00269     }
00270     latest_footstep_ = msg;
00271     Ogre::Quaternion orientation;
00272     Ogre::Vector3 position;
00273     if(!context_->getFrameManager()->getTransform( msg->header.frame_id,
00274                                                     msg->header.stamp,
00275                                                    position, orientation)) {
00276       ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00277                  msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00278       return;
00279     }
00280 
00281     // check thhe length of the shapes_
00282     allocateCubes(msg->footsteps.size());
00283     allocateTexts(msg->footsteps.size());
00284     line_->clear();
00285     line_->setLineWidth(0.01);
00286     line_->setNumLines(1);
00287     line_->setMaxPointsPerLine(1024);
00288 
00289     for (size_t i = 0; i < msg->footsteps.size(); i++)
00290     {
00291       ShapePtr shape = shapes_[i];
00292       rviz::MovableText* text = texts_[i];
00293       Ogre::SceneNode* node = text_nodes_[i];
00294       jsk_footstep_msgs::Footstep footstep = msg->footsteps[i];
00295       Ogre::Vector3 step_position;
00296       Ogre::Quaternion step_quaternion;
00297       if( !context_->getFrameManager()->transform( msg->header, footstep.pose,
00298                                                    step_position,
00299                                                    step_quaternion ))
00300       {
00301         ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
00302                    qPrintable( getName() ), msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00303         return;
00304       }
00305       shape->setPosition(step_position);
00306       shape->setOrientation(step_quaternion);
00307       // size of shape
00308       Ogre::Vector3 scale;
00309       if (footstep.dimensions.x == 0 &&
00310           footstep.dimensions.y == 0 &&
00311           footstep.dimensions.z == 0) {
00312         scale[0] = depth_;
00313         scale[1] = width_;
00314         scale[2] = height_;
00315       }
00316       else {
00317         scale[0] = footstep.dimensions.x;
00318         scale[1] = footstep.dimensions.y;
00319         scale[2] = footstep.dimensions.z;
00320       }
00321       shape->setScale(scale);      
00322       // update the size of text
00323       if (footstep.leg == jsk_footstep_msgs::Footstep::LEFT) {
00324         text->setCaption("L");
00325       }
00326       else if (footstep.leg == jsk_footstep_msgs::Footstep::RIGHT) {
00327         text->setCaption("R");
00328       }
00329       else {
00330         text->setCaption("unknown");
00331       }
00332       text->setCharacterHeight(estimateTextSize(footstep));
00333       node->setPosition(step_position);
00334       node->setOrientation(step_quaternion);
00335       text->setVisible(show_name_); // TODO
00336       line_->addPoint(step_position);
00337       
00338     }
00339     //updateFootstepSize();
00340     updateAlpha();
00341     context_->queueRender();
00342   }
00343 
00344 }
00345 
00346 #include <pluginlib/class_list_macros.h>
00347 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::FootstepDisplay, rviz::Display )


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