28 #include <boost/bind.hpp> 30 #include <OgreSceneNode.h> 31 #include <OgreSceneManager.h> 32 #include <OgreManualObject.h> 33 #include <OgreBillboardSet.h> 34 #include <OgreMatrix4.h> 55 "Color to draw neighbor links.",
this );
57 "Color to draw merged neighbor links.",
this );
59 "Color to draw global loop closure links.",
this );
61 "Color to draw local loop closure links.",
this );
63 "Color to draw user links.",
this );
65 "Color to draw virtual links.",
this );
68 "Amount of transparency to apply to the path.",
this );
100 if(!(msg->poses.size() == msg->posesId.size()))
102 ROS_ERROR(
"rtabmap_ros::MapGraph: Error pose ids and poses must have all the same size.");
107 std::map<int, rtabmap::Transform> poses;
108 std::multimap<int, rtabmap::Link> links;
114 Ogre::Vector3 position;
118 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable(
fixed_frame_ ));
121 Ogre::Matrix4 transform( orientation );
122 transform.setTrans( position );
126 Ogre::ColourValue color;
127 Ogre::ManualObject* manual_object =
scene_manager_->createManualObject();
128 manual_object->setDynamic(
true );
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)
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())
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 );
175 manual_object->end();
Ogre::ColourValue getOgreColor() const
virtual void onInitialize()
DisplayContext * context_
virtual float getFloat() const
virtual void reset()
Overridden from Display.
ColorProperty * color_global_property_
Ogre::SceneNode * scene_node_
FloatProperty * alpha_property_
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
virtual ~MapGraphDisplay()
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.
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)