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