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