odometry_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 "odometry_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 
00046 namespace rviz
00047 {
00048 
00049 OdometryDisplay::OdometryDisplay()
00050   : Display()
00051   , color_( 1.0f, 0.1f, 0.0f )
00052   , keep_(100)
00053   , position_tolerance_( 0.1 )
00054   , angle_tolerance_( 0.1 )
00055   , messages_received_(0)
00056 {
00057 }
00058 
00059 OdometryDisplay::~OdometryDisplay()
00060 {
00061   unsubscribe();
00062 
00063   clear();
00064 
00065   delete tf_filter_;
00066 }
00067 
00068 void OdometryDisplay::onInitialize()
00069 {
00070   tf_filter_ = new tf::MessageFilter<nav_msgs::Odometry>(*vis_manager_->getTFClient(), "", 5, update_nh_);
00071   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00072 
00073   tf_filter_->connectInput(sub_);
00074   tf_filter_->registerCallback(boost::bind(&OdometryDisplay::incomingMessage, this, _1));
00075   vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00076 }
00077 
00078 void OdometryDisplay::clear()
00079 {
00080   D_Arrow::iterator it = arrows_.begin();
00081   D_Arrow::iterator end = arrows_.end();
00082   for ( ; it != end; ++it )
00083   {
00084     delete *it;
00085   }
00086   arrows_.clear();
00087 
00088   if (last_used_message_)
00089   {
00090     last_used_message_.reset();
00091   }
00092 
00093   tf_filter_->clear();
00094 
00095   messages_received_ = 0;
00096   setStatus(status_levels::Warn, "Topic", "No messages received");
00097 }
00098 
00099 void OdometryDisplay::setTopic( const std::string& topic )
00100 {
00101   unsubscribe();
00102   topic_ = topic;
00103   clear();
00104   subscribe();
00105 
00106   propertyChanged(topic_property_);
00107 
00108   causeRender();
00109 }
00110 
00111 void OdometryDisplay::setColor( const Color& color )
00112 {
00113   color_ = color;
00114 
00115   D_Arrow::iterator it = arrows_.begin();
00116   D_Arrow::iterator end = arrows_.end();
00117   for ( ; it != end; ++it )
00118   {
00119     ogre_tools::Arrow* arrow = *it;
00120     arrow->setColor( color.r_, color.g_, color.b_, 1.0f );
00121   }
00122 
00123   propertyChanged(color_property_);
00124 
00125   causeRender();
00126 }
00127 
00128 void OdometryDisplay::setKeep(uint32_t keep)
00129 {
00130   keep_ = keep;
00131 
00132   propertyChanged(keep_property_);
00133 }
00134 
00135 void OdometryDisplay::setPositionTolerance( float tol )
00136 {
00137   position_tolerance_ = tol;
00138 
00139   propertyChanged(position_tolerance_property_);
00140 }
00141 
00142 void OdometryDisplay::setAngleTolerance( float tol )
00143 {
00144   angle_tolerance_ = tol;
00145 
00146   propertyChanged(angle_tolerance_property_);
00147 }
00148 
00149 void OdometryDisplay::subscribe()
00150 {
00151   if ( !isEnabled() )
00152   {
00153     return;
00154   }
00155 
00156   sub_.subscribe(update_nh_, topic_, 5);
00157 }
00158 
00159 void OdometryDisplay::unsubscribe()
00160 {
00161   sub_.unsubscribe();
00162 }
00163 
00164 void OdometryDisplay::onEnable()
00165 {
00166   scene_node_->setVisible( true );
00167   subscribe();
00168 }
00169 
00170 void OdometryDisplay::onDisable()
00171 {
00172   unsubscribe();
00173   clear();
00174   scene_node_->setVisible( false );
00175 }
00176 
00177 void OdometryDisplay::createProperties()
00178 {
00179   topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &OdometryDisplay::getTopic, this ),
00180                                                                                 boost::bind( &OdometryDisplay::setTopic, this, _1 ), parent_category_, this );
00181   setPropertyHelpText(topic_property_, "nav_msgs::Odometry topic to subscribe to.");
00182   ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00183   topic_prop->setMessageType(ros::message_traits::datatype<nav_msgs::Odometry>());
00184 
00185   color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &OdometryDisplay::getColor, this ),
00186                                                                           boost::bind( &OdometryDisplay::setColor, this, _1 ), parent_category_, this );
00187   setPropertyHelpText(color_property_, "Color of the arrows.");
00188 
00189   position_tolerance_property_ = property_manager_->createProperty<FloatProperty>( "Position Tolerance", property_prefix_, boost::bind( &OdometryDisplay::getPositionTolerance, this ),
00190                                                                                boost::bind( &OdometryDisplay::setPositionTolerance, this, _1 ), parent_category_, this );
00191   setPropertyHelpText(position_tolerance_property_, "Distance, in meters from the last arrow dropped, that will cause a new arrow to drop.");
00192   angle_tolerance_property_ = property_manager_->createProperty<FloatProperty>( "Angle Tolerance", property_prefix_, boost::bind( &OdometryDisplay::getAngleTolerance, this ),
00193                                                                                  boost::bind( &OdometryDisplay::setAngleTolerance, this, _1 ), parent_category_, this );
00194   setPropertyHelpText(angle_tolerance_property_, "Angular distance from the last arrow dropped, that will cause a new arrow to drop.");
00195 
00196   keep_property_ = property_manager_->createProperty<IntProperty>( "Keep", property_prefix_, boost::bind( &OdometryDisplay::getKeep, this ),
00197                                                                                boost::bind( &OdometryDisplay::setKeep, this, _1 ), parent_category_, this );
00198   setPropertyHelpText(keep_property_, "Number of arrows to keep before removing the oldest.");
00199 }
00200 
00201 bool validateFloats(const nav_msgs::Odometry& msg)
00202 {
00203   bool valid = true;
00204   valid = valid && validateFloats(msg.pose.pose);
00205   valid = valid && validateFloats(msg.twist.twist);
00206   return valid;
00207 }
00208 
00209 void OdometryDisplay::processMessage( const nav_msgs::Odometry::ConstPtr& message )
00210 {
00211   ++messages_received_;
00212 
00213   if (!validateFloats(*message))
00214   {
00215     setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00216     return;
00217   }
00218 
00219   {
00220     std::stringstream ss;
00221     ss << messages_received_ << " messages received";
00222     setStatus(status_levels::Ok, "Topic", ss.str());
00223   }
00224 
00225   if ( last_used_message_ )
00226   {
00227     Ogre::Vector3 last_position(last_used_message_->pose.pose.position.x, last_used_message_->pose.pose.position.y, last_used_message_->pose.pose.position.z);
00228     Ogre::Vector3 current_position(message->pose.pose.position.x, message->pose.pose.position.y, message->pose.pose.position.z);
00229     Ogre::Quaternion last_orientation(last_used_message_->pose.pose.orientation.w, last_used_message_->pose.pose.orientation.x, last_used_message_->pose.pose.orientation.y, last_used_message_->pose.pose.orientation.z);
00230     Ogre::Quaternion current_orientation(message->pose.pose.orientation.w, message->pose.pose.orientation.x, message->pose.pose.orientation.y, message->pose.pose.orientation.z);
00231 
00232     if ((last_position - current_position).length() < position_tolerance_ && (last_orientation - current_orientation).normalise() < angle_tolerance_)
00233     {
00234       return;
00235     }
00236   }
00237 
00238   ogre_tools::Arrow* arrow = new ogre_tools::Arrow( scene_manager_, scene_node_, 0.8f, 0.05f, 0.2f, 0.2f );
00239 
00240   transformArrow( message, arrow );
00241 
00242   arrow->setColor( color_.r_, color_.g_, color_.b_, 1.0f );
00243   arrow->setUserData( Ogre::Any((void*)this) );
00244 
00245   arrows_.push_back( arrow );
00246   last_used_message_ = message;
00247 }
00248 
00249 void OdometryDisplay::transformArrow( const nav_msgs::Odometry::ConstPtr& message, ogre_tools::Arrow* arrow )
00250 {
00251   Ogre::Vector3 position;
00252   Ogre::Quaternion orientation;
00253   if (!vis_manager_->getFrameManager()->transform(message->header, message->pose.pose, position, orientation))
00254   {
00255     ROS_ERROR( "Error transforming odometry '%s' from frame '%s' to frame '%s'", name_.c_str(), message->header.frame_id.c_str(), fixed_frame_.c_str() );
00256   }
00257 
00258   arrow->setPosition( position );
00259 
00260   // ogre_tools::Arrow points in -Z direction, so rotate the orientation before display.
00261   // TODO: is it safe to change ogre_tools::Arrow to point in +X direction?
00262   arrow->setOrientation( orientation * Ogre::Quaternion( Ogre::Degree( -90 ), Ogre::Vector3::UNIT_Y ));
00263 }
00264 
00265 void OdometryDisplay::targetFrameChanged()
00266 {
00267 }
00268 
00269 void OdometryDisplay::fixedFrameChanged()
00270 {
00271   tf_filter_->setTargetFrame( fixed_frame_ );
00272   clear();
00273 }
00274 
00275 void OdometryDisplay::update(float wall_dt, float ros_dt)
00276 {
00277   if (keep_ > 0)
00278   {
00279     while (arrows_.size() > keep_)
00280     {
00281       delete arrows_.front();
00282       arrows_.pop_front();
00283     }
00284   }
00285 }
00286 
00287 void OdometryDisplay::incomingMessage( const nav_msgs::Odometry::ConstPtr& message )
00288 {
00289   processMessage(message);
00290   causeRender();
00291 }
00292 
00293 void OdometryDisplay::reset()
00294 {
00295   Display::reset();
00296 
00297   clear();
00298 }
00299 
00300 } // namespace rviz


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