simple_occupancy_grid_array_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 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "simple_occupancy_grid_array_display.h"
00037 #include <Eigen/Geometry>
00038 #include <jsk_recognition_utils/pcl_conversion_util.h>
00039 #include <jsk_topic_tools/color_utils.h>
00040 #include "rviz_util.h"
00041 #include <jsk_recognition_utils/geo/plane.h>
00042 
00043 namespace jsk_rviz_plugins
00044 {
00045   SimpleOccupancyGridArrayDisplay::SimpleOccupancyGridArrayDisplay()
00046   {
00047     auto_color_property_ = new rviz::BoolProperty(
00048       "Auto Color", true,
00049       "Auto coloring",
00050       this, SLOT(updateAutoColor()));
00051     
00052     alpha_property_ = new rviz::FloatProperty(
00053       "Alpha", 1.0,
00054       "Amount of transparency to apply to the polygon.",
00055       this, SLOT(updateAlpha()));
00056 
00057     alpha_property_->setMin(0.0);
00058     alpha_property_->setMax(1.0);
00059 
00060     
00061   }
00062 
00063   SimpleOccupancyGridArrayDisplay::~SimpleOccupancyGridArrayDisplay()
00064   {
00065     delete alpha_property_;
00066     allocateCloudsAndNodes(0);
00067   }
00068 
00069   void SimpleOccupancyGridArrayDisplay::onInitialize()
00070   {
00071     MFDClass::onInitialize();
00072     updateAlpha();
00073     updateAutoColor();
00074   }
00075   
00076   void SimpleOccupancyGridArrayDisplay::allocateCloudsAndNodes(const size_t num)
00077   {
00078     if (num > clouds_.size()) { // need to allocate new node and clouds
00079       for (size_t i = clouds_.size(); i < num; i++) {
00080         Ogre::SceneNode* node = scene_node_->createChildSceneNode();
00081         rviz::PointCloud* cloud = new rviz::PointCloud();
00082         cloud->setRenderMode(rviz::PointCloud::RM_TILES);
00083         cloud->setCommonDirection( Ogre::Vector3::UNIT_Z );
00084         cloud->setCommonUpVector( Ogre::Vector3::UNIT_Y );
00085         node->attachObject(cloud);
00086         clouds_.push_back(cloud);
00087         nodes_.push_back(node);
00088       }
00089     }
00090     else if (num < clouds_.size()) // need to destroy
00091     {
00092       for (size_t i = num; i < clouds_.size(); i++) {
00093         nodes_[i]->detachObject(clouds_[i]);
00094         delete clouds_[i];
00095         scene_manager_->destroySceneNode(nodes_[i]);
00096       }
00097       clouds_.resize(num);
00098       nodes_.resize(num);
00099     }
00100   }
00101 
00102   void SimpleOccupancyGridArrayDisplay::reset()
00103   {
00104     MFDClass::reset();
00105     allocateCloudsAndNodes(0);
00106   }
00107 
00108   void SimpleOccupancyGridArrayDisplay::processMessage(
00109     const jsk_recognition_msgs::SimpleOccupancyGridArray::ConstPtr& msg)
00110   {
00111     Ogre::ColourValue white(1, 1, 1, 1);
00112     allocateCloudsAndNodes(msg->grids.size()); // not enough
00113     for (size_t i = 0; i < msg->grids.size(); i++) {
00114       Ogre::SceneNode* node = nodes_[i];
00115       rviz::PointCloud* cloud = clouds_[i];
00116       const jsk_recognition_msgs::SimpleOccupancyGrid grid = msg->grids[i];
00117       Ogre::Vector3 position;
00118       Ogre::Quaternion quaternion;
00119       
00120       // coefficients
00121       geometry_msgs::Pose plane_pose;
00122       jsk_recognition_utils::Plane::Ptr plane(new jsk_recognition_utils::Plane(grid.coefficients));
00123       Eigen::Affine3f plane_pose_eigen = plane->coordinates();
00124       tf::poseEigenToMsg(plane_pose_eigen, plane_pose);
00125       if(!context_->getFrameManager()->transform(grid.header, plane_pose,
00126                                                  position,
00127                                                  quaternion)) {
00128         ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
00129                    qPrintable( getName() ), grid.header.frame_id.c_str(),
00130                    qPrintable( fixed_frame_ ));
00131         return;                 // return?
00132       }
00133       node->setPosition(position);
00134       node->setOrientation(quaternion);
00135       cloud->setDimensions(grid.resolution, grid.resolution, 0.0);
00136       std::vector<rviz::PointCloud::Point> points;
00137       for (size_t ci = 0; ci < grid.cells.size(); ci++) {
00138         const geometry_msgs::Point p = grid.cells[ci];
00139         rviz::PointCloud::Point point;
00140         if (auto_color_) {
00141           point.color = rviz::colorMsgToOgre(jsk_topic_tools::colorCategory20(i));
00142         }
00143         else {
00144           point.color = white;
00145         }
00146         point.position.x = p.x;
00147         point.position.y = p.y;
00148         point.position.z = p.z;
00149         points.push_back(point);
00150       }
00151       cloud->clear();
00152       cloud->setAlpha(alpha_);
00153       if (!points.empty()) {
00154         cloud->addPoints(&points.front(), points.size());
00155       }
00156     }
00157     context_->queueRender();
00158   }
00159   
00160   void SimpleOccupancyGridArrayDisplay::updateAlpha()
00161   {
00162     alpha_ = alpha_property_->getFloat();
00163   }
00164 
00165   void SimpleOccupancyGridArrayDisplay::updateAutoColor()
00166   {
00167     auto_color_ = auto_color_property_->getBool();
00168   }
00169 
00170 }
00171 
00172 #include <pluginlib/class_list_macros.h>
00173 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::SimpleOccupancyGridArrayDisplay, rviz::Display )
00174 


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