$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 "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( const std::string& name, VisualizationManager* manager ) 00052 : Display( name, manager ) 00053 , color_( 0.1f, 1.0f, 0.0f ) 00054 , messages_received_(0) 00055 , tf_filter_(*manager->getTFClient(), "", 10, update_nh_) 00056 { 00057 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00058 00059 static int count = 0; 00060 std::stringstream ss; 00061 ss << "Path" << count++; 00062 manual_object_ = scene_manager_->createManualObject( ss.str() ); 00063 manual_object_->setDynamic( true ); 00064 scene_node_->attachObject( manual_object_ ); 00065 00066 setAlpha( 1.0f ); 00067 00068 tf_filter_.connectInput(sub_); 00069 tf_filter_.registerCallback(boost::bind(&PathDisplay::incomingMessage, this, _1)); 00070 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this); 00071 } 00072 00073 PathDisplay::~PathDisplay() 00074 { 00075 unsubscribe(); 00076 clear(); 00077 00078 scene_manager_->destroyManualObject( manual_object_ ); 00079 scene_manager_->destroySceneNode(scene_node_->getName()); 00080 } 00081 00082 void PathDisplay::clear() 00083 { 00084 manual_object_->clear(); 00085 00086 messages_received_ = 0; 00087 setStatus(status_levels::Warn, "Topic", "No messages received"); 00088 } 00089 00090 void PathDisplay::setTopic( const std::string& topic ) 00091 { 00092 unsubscribe(); 00093 topic_ = topic; 00094 clear(); 00095 subscribe(); 00096 00097 propertyChanged(topic_property_); 00098 00099 causeRender(); 00100 } 00101 00102 void PathDisplay::setColor( const Color& color ) 00103 { 00104 color_ = color; 00105 00106 propertyChanged(color_property_); 00107 00108 processMessage(current_message_); 00109 causeRender(); 00110 } 00111 00112 void PathDisplay::setAlpha( float alpha ) 00113 { 00114 alpha_ = alpha; 00115 00116 propertyChanged(alpha_property_); 00117 00118 processMessage(current_message_); 00119 causeRender(); 00120 } 00121 00122 void PathDisplay::subscribe() 00123 { 00124 if ( !isEnabled() ) 00125 { 00126 return; 00127 } 00128 00129 sub_.subscribe(update_nh_, topic_, 10); 00130 } 00131 00132 void PathDisplay::unsubscribe() 00133 { 00134 sub_.unsubscribe(); 00135 } 00136 00137 void PathDisplay::onEnable() 00138 { 00139 scene_node_->setVisible( true ); 00140 subscribe(); 00141 } 00142 00143 void PathDisplay::onDisable() 00144 { 00145 unsubscribe(); 00146 clear(); 00147 scene_node_->setVisible( false ); 00148 } 00149 00150 void PathDisplay::fixedFrameChanged() 00151 { 00152 clear(); 00153 00154 tf_filter_.setTargetFrame( fixed_frame_ ); 00155 } 00156 00157 void PathDisplay::update(float wall_dt, float ros_dt) 00158 { 00159 } 00160 00161 bool validateFloats(const nav_msgs::Path& msg) 00162 { 00163 bool valid = true; 00164 valid = valid && validateFloats(msg.poses); 00165 return valid; 00166 } 00167 00168 void PathDisplay::processMessage(const nav_msgs::Path::ConstPtr& msg) 00169 { 00170 if (!msg) 00171 { 00172 return; 00173 } 00174 00175 ++messages_received_; 00176 00177 if (!validateFloats(*msg)) 00178 { 00179 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); 00180 return; 00181 } 00182 00183 { 00184 std::stringstream ss; 00185 ss << messages_received_ << " messages received"; 00186 setStatus(status_levels::Ok, "Topic", ss.str()); 00187 } 00188 00189 manual_object_->clear(); 00190 00191 Ogre::Vector3 position; 00192 Ogre::Quaternion orientation; 00193 if (!vis_manager_->getFrameManager()->getTransform(msg->header, position, orientation)) 00194 { 00195 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() ); 00196 } 00197 00198 scene_node_->setPosition( position ); 00199 scene_node_->setOrientation( orientation ); 00200 00201 manual_object_->clear(); 00202 00203 Ogre::ColourValue color( color_.r_, color_.g_, color_.b_, alpha_ );; 00204 00205 uint32_t num_points = msg->poses.size(); 00206 manual_object_->estimateVertexCount( num_points ); 00207 manual_object_->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP ); 00208 for( uint32_t i=0; i < num_points; ++i) 00209 { 00210 Ogre::Vector3 pos(msg->poses[i].pose.position.x, msg->poses[i].pose.position.y, msg->poses[i].pose.position.z); 00211 manual_object_->position(pos); 00212 manual_object_->colour( color ); 00213 } 00214 00215 manual_object_->end(); 00216 } 00217 00218 void PathDisplay::incomingMessage(const nav_msgs::Path::ConstPtr& msg) 00219 { 00220 processMessage(msg); 00221 } 00222 00223 void PathDisplay::reset() 00224 { 00225 Display::reset(); 00226 clear(); 00227 } 00228 00229 void PathDisplay::createProperties() 00230 { 00231 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PathDisplay::getTopic, this ), 00232 boost::bind( &PathDisplay::setTopic, this, _1 ), parent_category_, this ); 00233 setPropertyHelpText(topic_property_, "geometry_msgs::Path topic to subscribe to."); 00234 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock(); 00235 topic_prop->setMessageType(ros::message_traits::datatype<nav_msgs::Path>()); 00236 00237 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &PathDisplay::getColor, this ), 00238 boost::bind( &PathDisplay::setColor, this, _1 ), parent_category_, this ); 00239 setPropertyHelpText(color_property_, "Color to draw the path."); 00240 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &PathDisplay::getAlpha, this ), 00241 boost::bind( &PathDisplay::setAlpha, this, _1 ), parent_category_, this ); 00242 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the path."); 00243 } 00244 00245 const char* PathDisplay::getDescription() 00246 { 00247 return "Displays data from a nav_msgs::Path message as lines."; 00248 } 00249 00250 } // namespace rviz 00251