MapGraphDisplay.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <boost/bind.hpp>
29 
30 #include <OgreSceneNode.h>
31 #include <OgreSceneManager.h>
32 #include <OgreManualObject.h>
33 #include <OgreBillboardSet.h>
34 #include <OgreMatrix4.h>
35 
36 #include <tf/transform_listener.h>
37 
38 #include <rviz/display_context.h>
39 #include <rviz/frame_manager.h>
43 
44 #include "MapGraphDisplay.h"
45 
46 #include <rtabmap/core/Link.h>
48 
49 namespace rtabmap_ros
50 {
51 
53 {
54  color_neighbor_property_ = new rviz::ColorProperty( "Neighbor", Qt::blue,
55  "Color to draw neighbor links.", this );
56  color_neighbor_merged_property_ = new rviz::ColorProperty( "Merged neighbor", QColor(255,170,0),
57  "Color to draw merged neighbor links.", this );
58  color_global_property_ = new rviz::ColorProperty( "Global loop closure", Qt::red,
59  "Color to draw global loop closure links.", this );
60  color_local_property_ = new rviz::ColorProperty( "Local loop closure", Qt::yellow,
61  "Color to draw local loop closure links.", this );
62  color_user_property_ = new rviz::ColorProperty( "User", Qt::red,
63  "Color to draw user links.", this );
64  color_virtual_property_ = new rviz::ColorProperty( "Virtual", Qt::magenta,
65  "Color to draw virtual links.", this );
66 
67  alpha_property_ = new rviz::FloatProperty( "Alpha", 1.0,
68  "Amount of transparency to apply to the path.", this );
69 }
70 
72 {
74 }
75 
77 {
80 }
81 
83 {
86 }
87 
89 {
90  for(unsigned int i=0; i<manual_objects_.size(); ++i)
91  {
92  manual_objects_[i]->clear();
93  scene_manager_->destroyManualObject( manual_objects_[i] );
94  }
95  manual_objects_.clear();
96 }
97 
98 void MapGraphDisplay::processMessage( const rtabmap_ros::MapGraph::ConstPtr& msg )
99 {
100  if(!(msg->poses.size() == msg->posesId.size()))
101  {
102  ROS_ERROR("rtabmap_ros::MapGraph: Error pose ids and poses must have all the same size.");
103  return;
104  }
105 
106  // Get links
107  std::map<int, rtabmap::Transform> poses;
108  std::multimap<int, rtabmap::Link> links;
109  rtabmap::Transform mapToOdom;
110  rtabmap_ros::mapGraphFromROS(*msg, poses, links, mapToOdom);
111 
112  destroyObjects();
113 
114  Ogre::Vector3 position;
115  Ogre::Quaternion orientation;
116  if( !context_->getFrameManager()->getTransform( msg->header, position, orientation ))
117  {
118  ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
119  }
120 
121  Ogre::Matrix4 transform( orientation );
122  transform.setTrans( position );
123 
124  if(links.size())
125  {
126  Ogre::ColourValue color;
127  Ogre::ManualObject* manual_object = scene_manager_->createManualObject();
128  manual_object->setDynamic( true );
129  scene_node_->attachObject( manual_object );
130  manual_objects_.push_back(manual_object);
131 
132  manual_object->estimateVertexCount(links.size() * 2);
133  manual_object->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST );
134  for(std::map<int, rtabmap::Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
135  {
136  std::map<int, rtabmap::Transform>::iterator poseIterFrom = poses.find(iter->second.from());
137  std::map<int, rtabmap::Transform>::iterator poseIterTo = poses.find(iter->second.to());
138  if(poseIterFrom != poses.end() && poseIterTo != poses.end())
139  {
140  if(iter->second.type() == rtabmap::Link::kNeighbor)
141  {
143  }
144  else if(iter->second.type() == rtabmap::Link::kNeighborMerged)
145  {
147  }
148  else if(iter->second.type() == rtabmap::Link::kVirtualClosure)
149  {
151  }
152  else if(iter->second.type() == rtabmap::Link::kUserClosure)
153  {
155  }
156  else if(iter->second.type() == rtabmap::Link::kLocalSpaceClosure || iter->second.type() == rtabmap::Link::kLocalTimeClosure)
157  {
159  }
160  else
161  {
163  }
164  color.a = alpha_property_->getFloat();
165  Ogre::Vector3 pos;
166  pos = transform * Ogre::Vector3( poseIterFrom->second.x(), poseIterFrom->second.y(), poseIterFrom->second.z() );
167  manual_object->position( pos.x, pos.y, pos.z );
168  manual_object->colour( color );
169  pos = transform * Ogre::Vector3( poseIterTo->second.x(), poseIterTo->second.y(), poseIterTo->second.z() );
170  manual_object->position( pos.x, pos.y, pos.z );
171  manual_object->colour( color );
172  }
173  }
174 
175  manual_object->end();
176  }
177 }
178 
179 } // namespace rtabmap_ros
180 
Ogre::ColourValue getOgreColor() const
DisplayContext * context_
virtual float getFloat() const
virtual void reset()
Overridden from Display.
ColorProperty * color_global_property_
Ogre::SceneNode * scene_node_
QString fixed_frame_
void mapGraphFromROS(const rtabmap_ros::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
virtual FrameManager * getFrameManager() const =0
ColorProperty * color_local_property_
Ogre::SceneManager * scene_manager_
ColorProperty * color_user_property_
ColorProperty * color_virtual_property_
void processMessage(const rtabmap_ros::MapGraph::ConstPtr &msg)
Overridden from MessageFilterDisplay.
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
std::vector< Ogre::ManualObject * > manual_objects_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
ColorProperty * color_neighbor_property_
Displays the graph of rtabmap::MapGraph message.
#define ROS_ERROR(...)
virtual void onInitialize()
Overridden from Display.
ColorProperty * color_neighbor_merged_property_
GLM_FUNC_DECL detail::tmat4x4< T, P > orientation(detail::tvec3< T, P > const &Normal, detail::tvec3< T, P > const &Up)
#define ROS_DEBUG(...)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:03