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