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 
00031 #include <boost/bind.hpp>
00032 
00033 #include <tf/transform_listener.h>
00034 
00035 #include "rviz/frame_manager.h"
00036 #include "rviz/ogre_helpers/arrow.h"
00037 #include "rviz/properties/color_property.h"
00038 #include "rviz/properties/float_property.h"
00039 #include "rviz/properties/int_property.h"
00040 #include "rviz/properties/ros_topic_property.h"
00041 #include "rviz/validate_floats.h"
00042 #include "rviz/display_context.h"
00043 
00044 #include "odometry_display.h"
00045 
00046 namespace rviz
00047 {
00048 
00049 OdometryDisplay::OdometryDisplay()
00050   : Display()
00051   , messages_received_(0)
00052 {
00053   topic_property_ = new RosTopicProperty( "Topic", "",
00054                                           QString::fromStdString( ros::message_traits::datatype<nav_msgs::Odometry>() ),
00055                                           "nav_msgs::Odometry topic to subscribe to.",
00056                                           this, SLOT( updateTopic() ));
00057 
00058   color_property_ = new ColorProperty( "Color", QColor( 255, 25, 0 ),
00059                                        "Color of the arrows.",
00060                                        this, SLOT( updateColor() ));
00061 
00062   position_tolerance_property_ = new FloatProperty( "Position Tolerance", .1,
00063                                                     "Distance, in meters from the last arrow dropped, "
00064                                                     "that will cause a new arrow to drop.",
00065                                                     this );
00066   position_tolerance_property_->setMin( 0 );
00067                                                 
00068   angle_tolerance_property_ = new FloatProperty( "Angle Tolerance", .1,
00069                                                  "Angular distance from the last arrow dropped, "
00070                                                  "that will cause a new arrow to drop.",
00071                                                  this );
00072   angle_tolerance_property_->setMin( 0 );
00073 
00074   keep_property_ = new IntProperty( "Keep", 100,
00075                                     "Number of arrows to keep before removing the oldest.  0 means keep all of them.",
00076                                     this );
00077   keep_property_->setMin( 0 );
00078 
00079   length_property_ = new FloatProperty( "Length", 1.0,
00080                                         "Length of each arrow.",
00081                                         this, SLOT( updateLength() ));
00082 }
00083 
00084 OdometryDisplay::~OdometryDisplay()
00085 {
00086   unsubscribe();
00087   clear();
00088   delete tf_filter_;
00089 }
00090 
00091 void OdometryDisplay::onInitialize()
00092 {
00093   tf_filter_ = new tf::MessageFilter<nav_msgs::Odometry>( *context_->getTFClient(), fixed_frame_.toStdString(),
00094                                                           5, update_nh_ );
00095 
00096   tf_filter_->connectInput( sub_ );
00097   tf_filter_->registerCallback( boost::bind( &OdometryDisplay::incomingMessage, this, _1 ));
00098   context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );
00099 }
00100 
00101 void OdometryDisplay::clear()
00102 {
00103   D_Arrow::iterator it = arrows_.begin();
00104   D_Arrow::iterator end = arrows_.end();
00105   for ( ; it != end; ++it )
00106   {
00107     delete *it;
00108   }
00109   arrows_.clear();
00110 
00111   if( last_used_message_ )
00112   {
00113     last_used_message_.reset();
00114   }
00115 
00116   tf_filter_->clear();
00117 
00118   messages_received_ = 0;
00119   setStatus( StatusProperty::Warn, "Topic", "No messages received" );
00120 }
00121 
00122 void OdometryDisplay::updateTopic()
00123 {
00124   unsubscribe();
00125   clear();
00126   subscribe();
00127   context_->queueRender();
00128 }
00129 
00130 void OdometryDisplay::updateColor()
00131 {
00132   QColor color = color_property_->getColor();
00133   float red   = color.redF();
00134   float green = color.greenF();
00135   float blue  = color.blueF();
00136 
00137   D_Arrow::iterator it = arrows_.begin();
00138   D_Arrow::iterator end = arrows_.end();
00139   for( ; it != end; ++it )
00140   {
00141     Arrow* arrow = *it;
00142     arrow->setColor( red, green, blue, 1.0f );
00143   }
00144   context_->queueRender();
00145 }
00146 
00147 void OdometryDisplay::updateLength()
00148 {
00149   float length = length_property_->getFloat();
00150   D_Arrow::iterator it = arrows_.begin();
00151   D_Arrow::iterator end = arrows_.end();
00152   Ogre::Vector3 scale( length, length, length );
00153   for ( ; it != end; ++it )
00154   {
00155     Arrow* arrow = *it;
00156     arrow->setScale( scale );
00157   }
00158   context_->queueRender();
00159 }
00160 
00161 void OdometryDisplay::subscribe()
00162 {
00163   if ( !isEnabled() )
00164   {
00165     return;
00166   }
00167 
00168   try
00169   {
00170     sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 5 );
00171     setStatus( StatusProperty::Ok, "Topic", "OK" );
00172   }
00173   catch( ros::Exception& e )
00174   {
00175     setStatus( StatusProperty::Error, "Topic", QString( "Error subscribing: " ) + e.what() );
00176   }
00177 }
00178 
00179 void OdometryDisplay::unsubscribe()
00180 {
00181   sub_.unsubscribe();
00182 }
00183 
00184 void OdometryDisplay::onEnable()
00185 {
00186   subscribe();
00187 }
00188 
00189 void OdometryDisplay::onDisable()
00190 {
00191   unsubscribe();
00192   clear();
00193 }
00194 
00195 bool validateFloats(const nav_msgs::Odometry& msg)
00196 {
00197   bool valid = true;
00198   valid = valid && validateFloats( msg.pose.pose );
00199   valid = valid && validateFloats( msg.twist.twist );
00200   return valid;
00201 }
00202 
00203 void OdometryDisplay::incomingMessage( const nav_msgs::Odometry::ConstPtr& message )
00204 {
00205   ++messages_received_;
00206 
00207   if( !validateFloats( *message ))
00208   {
00209     setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
00210     return;
00211   }
00212 
00213   setStatus( StatusProperty::Ok, "Topic", QString::number( messages_received_ ) + " messages received" );
00214 
00215   if( last_used_message_ )
00216   {
00217     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);
00218     Ogre::Vector3 current_position(message->pose.pose.position.x, message->pose.pose.position.y, message->pose.pose.position.z);
00219     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);
00220     Ogre::Quaternion current_orientation(message->pose.pose.orientation.w, message->pose.pose.orientation.x, message->pose.pose.orientation.y, message->pose.pose.orientation.z);
00221 
00222     if( (last_position - current_position).length() < position_tolerance_property_->getFloat() &&
00223         (last_orientation - current_orientation).normalise() < angle_tolerance_property_->getFloat() )
00224     {
00225       return;
00226     }
00227   }
00228 
00229   Arrow* arrow = new Arrow( scene_manager_, scene_node_, 0.8f, 0.05f, 0.2f, 0.2f );
00230 
00231   transformArrow( message, arrow );
00232 
00233   QColor color = color_property_->getColor();
00234   arrow->setColor( color.redF(), color.greenF(), color.blueF(), 1.0f );
00235 
00236   float length = length_property_->getFloat();
00237   Ogre::Vector3 scale( length, length, length );
00238   arrow->setScale( scale );
00239 
00240   arrows_.push_back( arrow );
00241 
00242   last_used_message_ = message;
00243   context_->queueRender();
00244 }
00245 
00246 void OdometryDisplay::transformArrow( const nav_msgs::Odometry::ConstPtr& message, Arrow* arrow )
00247 {
00248   Ogre::Vector3 position;
00249   Ogre::Quaternion orientation;
00250   if( !context_->getFrameManager()->transform( message->header, message->pose.pose, position, orientation ))
00251   {
00252     ROS_ERROR( "Error transforming odometry '%s' from frame '%s' to frame '%s'",
00253                qPrintable( getName() ), message->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00254   }
00255 
00256   arrow->setPosition( position );
00257 
00258   // Arrow points in -Z direction, so rotate the orientation before display.
00259   // TODO: is it safe to change Arrow to point in +X direction?
00260   arrow->setOrientation( orientation * Ogre::Quaternion( Ogre::Degree( -90 ), Ogre::Vector3::UNIT_Y ));
00261 }
00262 
00263 void OdometryDisplay::fixedFrameChanged()
00264 {
00265   tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
00266   clear();
00267 }
00268 
00269 void OdometryDisplay::update( float wall_dt, float ros_dt )
00270 {
00271   size_t keep = keep_property_->getInt();
00272   if( keep > 0 )
00273   {
00274     while( arrows_.size() > keep )
00275     {
00276       delete arrows_.front();
00277       arrows_.pop_front();
00278     }
00279   }
00280 }
00281 
00282 void OdometryDisplay::reset()
00283 {
00284   Display::reset();
00285   clear();
00286 }
00287 
00288 } // namespace rviz
00289 
00290 #include <pluginlib/class_list_macros.h>
00291 PLUGINLIB_EXPORT_CLASS( rviz::OdometryDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35