path_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
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  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "path_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/properties/property.h"
00033 #include "rviz/properties/property_manager.h"
00034 #include "rviz/frame_manager.h"
00035 #include "rviz/validate_floats.h"
00036 
00037 #include "ogre_tools/arrow.h"
00038 
00039 #include <tf/transform_listener.h>
00040 
00041 #include <boost/bind.hpp>
00042 
00043 #include <OGRE/OgreSceneNode.h>
00044 #include <OGRE/OgreSceneManager.h>
00045 #include <OGRE/OgreManualObject.h>
00046 #include <OGRE/OgreBillboardSet.h>
00047 
00048 namespace rviz
00049 {
00050 
00051 PathDisplay::PathDisplay()
00052   : Display()
00053   , color_( 0.1f, 1.0f, 0.0f )
00054   , messages_received_(0)
00055 {
00056 }
00057 
00058 PathDisplay::~PathDisplay()
00059 {
00060   unsubscribe();
00061   clear();
00062 
00063   scene_manager_->destroyManualObject( manual_object_ );
00064   scene_manager_->destroySceneNode(scene_node_->getName());
00065   delete tf_filter_;
00066 }
00067 
00068 void PathDisplay::onInitialize()
00069 {
00070   tf_filter_ = new tf::MessageFilter<nav_msgs::Path>(*vis_manager_->getTFClient(), "", 10, update_nh_);
00071   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00072 
00073   static int count = 0;
00074   std::stringstream ss;
00075   ss << "Path" << count++;
00076   manual_object_ = scene_manager_->createManualObject( ss.str() );
00077   manual_object_->setDynamic( true );
00078   scene_node_->attachObject( manual_object_ );
00079 
00080   setAlpha( 1.0f );
00081 
00082   tf_filter_->connectInput(sub_);
00083   tf_filter_->registerCallback(boost::bind(&PathDisplay::incomingMessage, this, _1));
00084   vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00085 }
00086 
00087 void PathDisplay::clear()
00088 {
00089   manual_object_->clear();
00090 
00091   messages_received_ = 0;
00092   setStatus(status_levels::Warn, "Topic", "No messages received");
00093 }
00094 
00095 void PathDisplay::setTopic( const std::string& topic )
00096 {
00097   unsubscribe();
00098   topic_ = topic;
00099   clear();
00100   subscribe();
00101 
00102   propertyChanged(topic_property_);
00103 
00104   causeRender();
00105 }
00106 
00107 void PathDisplay::setColor( const Color& color )
00108 {
00109   color_ = color;
00110 
00111   propertyChanged(color_property_);
00112 
00113   processMessage(current_message_);
00114   causeRender();
00115 }
00116 
00117 void PathDisplay::setAlpha( float alpha )
00118 {
00119   alpha_ = alpha;
00120 
00121   propertyChanged(alpha_property_);
00122 
00123   processMessage(current_message_);
00124   causeRender();
00125 }
00126 
00127 void PathDisplay::subscribe()
00128 {
00129   if ( !isEnabled() )
00130   {
00131     return;
00132   }
00133 
00134   sub_.subscribe(update_nh_, topic_, 10);
00135 }
00136 
00137 void PathDisplay::unsubscribe()
00138 {
00139   sub_.unsubscribe();
00140 }
00141 
00142 void PathDisplay::onEnable()
00143 {
00144   scene_node_->setVisible( true );
00145   subscribe();
00146 }
00147 
00148 void PathDisplay::onDisable()
00149 {
00150   unsubscribe();
00151   clear();
00152   scene_node_->setVisible( false );
00153 }
00154 
00155 void PathDisplay::fixedFrameChanged()
00156 {
00157   clear();
00158 
00159   tf_filter_->setTargetFrame( fixed_frame_ );
00160 }
00161 
00162 void PathDisplay::update(float wall_dt, float ros_dt)
00163 {
00164 }
00165 
00166 bool validateFloats(const nav_msgs::Path& msg)
00167 {
00168   bool valid = true;
00169   valid = valid && validateFloats(msg.poses);
00170   return valid;
00171 }
00172 
00173 void PathDisplay::processMessage(const nav_msgs::Path::ConstPtr& msg)
00174 {
00175   if (!msg)
00176   {
00177     return;
00178   }
00179 
00180   ++messages_received_;
00181 
00182   if (!validateFloats(*msg))
00183   {
00184     setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00185     return;
00186   }
00187 
00188   {
00189     std::stringstream ss;
00190     ss << messages_received_ << " messages received";
00191     setStatus(status_levels::Ok, "Topic", ss.str());
00192   }
00193 
00194   manual_object_->clear();
00195 
00196   Ogre::Vector3 position;
00197   Ogre::Quaternion orientation;
00198   if (!vis_manager_->getFrameManager()->getTransform(msg->header, position, orientation))
00199   {
00200     ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() );
00201   }
00202 
00203   scene_node_->setPosition( position );
00204   scene_node_->setOrientation( orientation );
00205 
00206   manual_object_->clear();
00207 
00208   Ogre::ColourValue color( color_.r_, color_.g_, color_.b_, alpha_ );;
00209 
00210   uint32_t num_points = msg->poses.size();
00211   manual_object_->estimateVertexCount( num_points );
00212   manual_object_->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP );
00213   for( uint32_t i=0; i < num_points; ++i)
00214   {
00215     Ogre::Vector3 pos(msg->poses[i].pose.position.x, msg->poses[i].pose.position.y, msg->poses[i].pose.position.z);
00216     manual_object_->position(pos);
00217     manual_object_->colour( color );
00218   }
00219 
00220   manual_object_->end();
00221 }
00222 
00223 void PathDisplay::incomingMessage(const nav_msgs::Path::ConstPtr& msg)
00224 {
00225   processMessage(msg);
00226 }
00227 
00228 void PathDisplay::reset()
00229 {
00230   Display::reset();
00231   clear();
00232 }
00233 
00234 void PathDisplay::createProperties()
00235 {
00236   topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PathDisplay::getTopic, this ),
00237                                                                                 boost::bind( &PathDisplay::setTopic, this, _1 ), parent_category_, this );
00238   setPropertyHelpText(topic_property_, "geometry_msgs::Path topic to subscribe to.");
00239   ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00240   topic_prop->setMessageType(ros::message_traits::datatype<nav_msgs::Path>());
00241 
00242   color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &PathDisplay::getColor, this ),
00243                                                                       boost::bind( &PathDisplay::setColor, this, _1 ), parent_category_, this );
00244   setPropertyHelpText(color_property_, "Color to draw the path.");
00245   alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &PathDisplay::getAlpha, this ),
00246                                                                        boost::bind( &PathDisplay::setAlpha, this, _1 ), parent_category_, this );
00247   setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the path.");
00248 }
00249 
00250 const char* PathDisplay::getDescription()
00251 {
00252   return "Displays data from a nav_msgs::Path message as lines.";
00253 }
00254 
00255 } // namespace rviz
00256 


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:53