MapGraphDisplay.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <boost/bind.hpp>
00029 
00030 #include <OgreSceneNode.h>
00031 #include <OgreSceneManager.h>
00032 #include <OgreManualObject.h>
00033 #include <OgreBillboardSet.h>
00034 #include <OgreMatrix4.h>
00035 
00036 #include <tf/transform_listener.h>
00037 
00038 #include <rviz/display_context.h>
00039 #include <rviz/frame_manager.h>
00040 #include "rviz/properties/color_property.h"
00041 #include "rviz/properties/float_property.h"
00042 #include "rviz/properties/int_property.h"
00043 
00044 #include "MapGraphDisplay.h"
00045 
00046 #include <rtabmap/core/Link.h>
00047 #include <rtabmap_ros/MsgConversion.h>
00048 
00049 namespace rtabmap_ros
00050 {
00051 
00052 MapGraphDisplay::MapGraphDisplay()
00053 {
00054         color_neighbor_property_ = new rviz::ColorProperty( "Neighbor", Qt::blue,
00055                                        "Color to draw neighbor links.", this );
00056         color_global_property_ = new rviz::ColorProperty( "Global loop closure", Qt::red,
00057                                                "Color to draw global loop closure links.", this );
00058         color_local_property_ = new rviz::ColorProperty( "Local loop closure", Qt::yellow,
00059                                                "Color to draw local loop closure links.", this );
00060         color_user_property_ = new rviz::ColorProperty( "User", Qt::red,
00061                                                "Color to draw user links.", this );
00062         color_virtual_property_ = new rviz::ColorProperty( "Virtual", Qt::magenta,
00063                                                "Color to draw virtual links.", this );
00064 
00065         alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
00066                                        "Amount of transparency to apply to the path.", this );
00067 }
00068 
00069 MapGraphDisplay::~MapGraphDisplay()
00070 {
00071         destroyObjects();
00072 }
00073 
00074 void MapGraphDisplay::onInitialize()
00075 {
00076   MFDClass::onInitialize();
00077   destroyObjects();
00078 }
00079 
00080 void MapGraphDisplay::reset()
00081 {
00082   MFDClass::reset();
00083   destroyObjects();
00084 }
00085 
00086 void MapGraphDisplay::destroyObjects()
00087 {
00088         for(unsigned int i=0; i<manual_objects_.size(); ++i)
00089         {
00090                 manual_objects_[i]->clear();
00091                 scene_manager_->destroyManualObject( manual_objects_[i] );
00092         }
00093         manual_objects_.clear();
00094 }
00095 
00096 void MapGraphDisplay::processMessage( const rtabmap_ros::MapData::ConstPtr& msg )
00097 {
00098         if(!(msg->graph.mapIds.size() == msg->graph.nodeIds.size() && msg->graph.poses.size() == msg->graph.nodeIds.size()))
00099         {
00100                 ROS_ERROR("rtabmap_ros::MapGraph: Error map ids, pose ids and poses must have all the same size.");
00101                 return;
00102         }
00103 
00104         // Get links
00105         std::map<int, rtabmap::Transform> poses;
00106         std::map<int, int> mapIds;
00107         std::map<int,  double> stamps;
00108         std::map<int, std::string> labels;
00109         std::map<int, std::vector<unsigned char> > userDatas;
00110         std::multimap<int, rtabmap::Link> links;
00111         rtabmap::Transform mapToOdom;
00112         rtabmap_ros::mapGraphFromROS(msg->graph, poses, mapIds, stamps, labels, userDatas, links, mapToOdom);
00113 
00114         destroyObjects();
00115 
00116         Ogre::Vector3 position;
00117         Ogre::Quaternion orientation;
00118         if( !context_->getFrameManager()->getTransform( msg->header, position, orientation ))
00119         {
00120                 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00121         }
00122 
00123         Ogre::Matrix4 transform( orientation );
00124         transform.setTrans( position );
00125 
00126         if(links.size())
00127         {
00128                 Ogre::ColourValue color;
00129                 Ogre::ManualObject* manual_object = scene_manager_->createManualObject();
00130                 manual_object->setDynamic( true );
00131                 scene_node_->attachObject( manual_object );
00132                 manual_objects_.push_back(manual_object);
00133 
00134                 manual_object->estimateVertexCount(links.size() * 2);
00135                 manual_object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST );
00136                 for(std::map<int, rtabmap::Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
00137                 {
00138                         std::map<int, rtabmap::Transform>::iterator poseIterFrom = poses.find(iter->second.from());
00139                         std::map<int, rtabmap::Transform>::iterator poseIterTo = poses.find(iter->second.to());
00140                         if(poseIterFrom != poses.end() && poseIterTo != poses.end())
00141                         {
00142                                 if(iter->second.type() == rtabmap::Link::kNeighbor)
00143                                 {
00144                                         color = color_neighbor_property_->getOgreColor();
00145                                 }
00146                                 else if(iter->second.type() == rtabmap::Link::kVirtualClosure)
00147                                 {
00148                                         color = color_virtual_property_->getOgreColor();
00149                                 }
00150                                 else if(iter->second.type() == rtabmap::Link::kUserClosure)
00151                                 {
00152                                         color = color_user_property_->getOgreColor();
00153                                 }
00154                                 else if(iter->second.type() == rtabmap::Link::kLocalSpaceClosure || iter->second.type() == rtabmap::Link::kLocalTimeClosure)
00155                                 {
00156                                         color = color_local_property_->getOgreColor();
00157                                 }
00158                                 else
00159                                 {
00160                                         color = color_global_property_->getOgreColor();
00161                                 }
00162                                 color.a = alpha_property_->getFloat();
00163                                 Ogre::Vector3 pos;
00164                                 pos = transform * Ogre::Vector3( poseIterFrom->second.x(), poseIterFrom->second.y(), poseIterFrom->second.z() );
00165                                 manual_object->position( pos.x, pos.y, pos.z );
00166                                 manual_object->colour( color );
00167                                 pos = transform * Ogre::Vector3( poseIterTo->second.x(), poseIterTo->second.y(), poseIterTo->second.z() );
00168                                 manual_object->position( pos.x, pos.y, pos.z );
00169                                 manual_object->colour( color );
00170                         }
00171                 }
00172 
00173                 manual_object->end();
00174         }
00175 }
00176 
00177 } // namespace rtabmap_ros
00178 
00179 #include <pluginlib/class_list_macros.h>
00180 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::MapGraphDisplay, rviz::Display )


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24