$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_display.h" 00031 #include "rviz/visualization_manager.h" 00032 #include "rviz/properties/property.h" 00033 #include "rviz/properties/property_manager.h" 00034 #include "rviz/selection/selection_manager.h" 00035 #include "rviz/frame_manager.h" 00036 #include "rviz/validate_floats.h" 00037 00038 #include "ogre_tools/arrow.h" 00039 #include "ogre_tools/axes.h" 00040 00041 #include <tf/transform_listener.h> 00042 00043 #include <boost/bind.hpp> 00044 00045 #include <OGRE/OgreSceneNode.h> 00046 #include <OGRE/OgreSceneManager.h> 00047 00048 namespace rviz 00049 { 00050 00051 class PoseDisplaySelectionHandler : public SelectionHandler 00052 { 00053 public: 00054 PoseDisplaySelectionHandler(const std::string& name) 00055 : name_(name) 00056 {} 00057 00058 void createProperties(const Picked& obj, PropertyManager* property_manager) 00059 { 00060 std::stringstream prefix; 00061 prefix << "Pose " << name_; 00062 CategoryPropertyWPtr cat = property_manager->createCategory(prefix.str(), prefix.str()); 00063 properties_.push_back(property_manager->createProperty<StringProperty>("Frame", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getFrame, this), StringProperty::Setter(), cat)); 00064 properties_.push_back(property_manager->createProperty<Vector3Property>("Position", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getPosition, this), Vector3Property::Setter(), cat)); 00065 properties_.push_back(property_manager->createProperty<QuaternionProperty>("Orientation", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getOrientation, this), QuaternionProperty::Setter(), cat)); 00066 } 00067 00068 void setMessage(const geometry_msgs::PoseStampedConstPtr& message) 00069 { 00070 message_ = message; 00071 } 00072 00073 std::string getFrame() 00074 { 00075 return message_->header.frame_id; 00076 } 00077 00078 Ogre::Vector3 getPosition() 00079 { 00080 return Ogre::Vector3(message_->pose.position.x, message_->pose.position.y, message_->pose.position.z); 00081 } 00082 00083 Ogre::Quaternion getOrientation() 00084 { 00085 return Ogre::Quaternion(message_->pose.orientation.x, message_->pose.orientation.y, message_->pose.orientation.z, message_->pose.orientation.w); 00086 } 00087 00088 private: 00089 std::string name_; 00090 geometry_msgs::PoseStampedConstPtr message_; 00091 }; 00092 00093 PoseDisplay::PoseDisplay( const std::string& name, VisualizationManager* manager ) 00094 : Display( name, manager ) 00095 , color_( 1.0f, 0.1f, 0.0f ) 00096 , head_radius_(0.2) 00097 , head_length_(0.3) 00098 , shaft_radius_(0.1) 00099 , shaft_length_(1.0) 00100 , axes_length_(1.0) 00101 , axes_radius_(0.1) 00102 , messages_received_(0) 00103 , tf_filter_(*manager->getTFClient(), "", 5, update_nh_) 00104 { 00105 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00106 00107 tf_filter_.connectInput(sub_); 00108 tf_filter_.registerCallback(boost::bind(&PoseDisplay::incomingMessage, this, _1)); 00109 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this); 00110 00111 arrow_ = new ogre_tools::Arrow(scene_manager_, scene_node_, shaft_length_, shaft_radius_, head_length_, head_radius_); 00112 // ogre_tools::Arrow points in -Z direction, so rotate the orientation before display. 00113 // TODO: is it safe to change ogre_tools::Arrow to point in +X direction? 00114 arrow_->setOrientation( Ogre::Quaternion( Ogre::Degree( -90 ), Ogre::Vector3::UNIT_Y )); 00115 00116 axes_ = new ogre_tools::Axes(scene_manager_, scene_node_, axes_length_, axes_radius_); 00117 00118 setVisibility(); 00119 00120 Ogre::Quaternion quat(Ogre::Quaternion::IDENTITY); 00121 axes_->setOrientation(quat); 00122 00123 SelectionManager* sel_manager = vis_manager_->getSelectionManager(); 00124 coll_handler_.reset(new PoseDisplaySelectionHandler(name_)); 00125 coll_ = sel_manager->createCollisionForObject(arrow_, coll_handler_); 00126 sel_manager->createCollisionForObject(axes_, coll_handler_, coll_); 00127 00128 setShape(Arrow); 00129 setAlpha(1.0); 00130 } 00131 00132 PoseDisplay::~PoseDisplay() 00133 { 00134 unsubscribe(); 00135 00136 clear(); 00137 00138 SelectionManager* sel_manager = vis_manager_->getSelectionManager(); 00139 sel_manager->removeObject(coll_); 00140 00141 delete arrow_; 00142 delete axes_; 00143 } 00144 00145 void PoseDisplay::clear() 00146 { 00147 tf_filter_.clear(); 00148 latest_message_.reset(); 00149 setVisibility(); 00150 00151 messages_received_ = 0; 00152 setStatus(status_levels::Warn, "Topic", "No messages received"); 00153 } 00154 00155 void PoseDisplay::setTopic( const std::string& topic ) 00156 { 00157 unsubscribe(); 00158 topic_ = topic; 00159 subscribe(); 00160 00161 propertyChanged(topic_property_); 00162 00163 causeRender(); 00164 } 00165 00166 void PoseDisplay::setColor( const Color& color ) 00167 { 00168 color_ = color; 00169 00170 arrow_->setColor(color.r_, color.g_, color.b_, alpha_); 00171 axes_->setColor(color.r_, color.g_, color.b_, alpha_); 00172 00173 propertyChanged(color_property_); 00174 00175 causeRender(); 00176 } 00177 00178 void PoseDisplay::setAlpha( float a ) 00179 { 00180 alpha_ = a; 00181 00182 arrow_->setColor(color_.r_, color_.g_, color_.b_, alpha_); 00183 axes_->setColor(color_.r_, color_.g_, color_.b_, alpha_); 00184 00185 propertyChanged(alpha_property_); 00186 00187 causeRender(); 00188 } 00189 00190 void PoseDisplay::setHeadRadius(float r) 00191 { 00192 head_radius_ = r; 00193 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_); 00194 propertyChanged(head_radius_property_); 00195 } 00196 00197 void PoseDisplay::setHeadLength(float l) 00198 { 00199 head_length_ = l; 00200 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_); 00201 propertyChanged(head_length_property_); 00202 } 00203 00204 void PoseDisplay::setShaftRadius(float r) 00205 { 00206 shaft_radius_ = r; 00207 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_); 00208 propertyChanged(shaft_radius_property_); 00209 } 00210 00211 void PoseDisplay::setShaftLength(float l) 00212 { 00213 shaft_length_ = l; 00214 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_); 00215 propertyChanged(shaft_length_property_); 00216 } 00217 00218 void PoseDisplay::setAxesRadius(float r) 00219 { 00220 axes_radius_ = r; 00221 axes_->set(axes_length_, axes_radius_); 00222 propertyChanged(axes_radius_property_); 00223 } 00224 00225 void PoseDisplay::setAxesLength(float l) 00226 { 00227 axes_length_ = l; 00228 axes_->set(axes_length_, axes_radius_); 00229 propertyChanged(axes_length_property_); 00230 } 00231 00232 void PoseDisplay::setShape(int shape) 00233 { 00234 current_shape_ = (Shape)shape; 00235 00236 setVisibility(); 00237 00238 propertyChanged(shape_property_); 00239 00240 createShapeProperties(); 00241 00242 causeRender(); 00243 } 00244 00245 void PoseDisplay::setVisibility() 00246 { 00247 arrow_->getSceneNode()->setVisible(false); 00248 axes_->getSceneNode()->setVisible(false); 00249 00250 if (!latest_message_) 00251 { 00252 return; 00253 } 00254 00255 switch (current_shape_) 00256 { 00257 case Arrow: 00258 arrow_->getSceneNode()->setVisible(true); 00259 break; 00260 case Axes: 00261 axes_->getSceneNode()->setVisible(true); 00262 break; 00263 } 00264 } 00265 00266 void PoseDisplay::subscribe() 00267 { 00268 if ( !isEnabled() ) 00269 { 00270 return; 00271 } 00272 00273 sub_.subscribe(update_nh_, topic_, 5); 00274 } 00275 00276 void PoseDisplay::unsubscribe() 00277 { 00278 sub_.unsubscribe(); 00279 } 00280 00281 void PoseDisplay::onEnable() 00282 { 00283 setVisibility(); 00284 00285 subscribe(); 00286 } 00287 00288 void PoseDisplay::onDisable() 00289 { 00290 unsubscribe(); 00291 clear(); 00292 scene_node_->setVisible( false ); 00293 } 00294 00295 void PoseDisplay::createShapeProperties() 00296 { 00297 if (!property_manager_) 00298 { 00299 return; 00300 } 00301 00302 property_manager_->deleteProperty(shape_category_.lock()); 00303 shape_category_ = property_manager_->createCategory("Shape Properties", property_prefix_, parent_category_, this); 00304 00305 switch (current_shape_) 00306 { 00307 case Arrow: 00308 { 00309 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &PoseDisplay::getColor, this ), 00310 boost::bind( &PoseDisplay::setColor, this, _1 ), shape_category_, this ); 00311 setPropertyHelpText(color_property_, "Color to draw the arrow."); 00312 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &PoseDisplay::getAlpha, this ), 00313 boost::bind( &PoseDisplay::setAlpha, this, _1 ), shape_category_, this ); 00314 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the arrow."); 00315 FloatPropertyPtr float_prop = alpha_property_.lock(); 00316 float_prop->setMin(0.0); 00317 float_prop->setMax(1.0); 00318 00319 shaft_length_property_ = property_manager_->createProperty<FloatProperty>( "Shaft Length", property_prefix_, boost::bind( &PoseDisplay::getShaftLength, this ), 00320 boost::bind( &PoseDisplay::setShaftLength, this, _1 ), shape_category_, this ); 00321 setPropertyHelpText(shaft_length_property_, "Length of the arrow's shaft, in meters."); 00322 shaft_radius_property_ = property_manager_->createProperty<FloatProperty>( "Shaft Radius", property_prefix_, boost::bind( &PoseDisplay::getShaftRadius, this ), 00323 boost::bind( &PoseDisplay::setShaftRadius, this, _1 ), shape_category_, this ); 00324 setPropertyHelpText(shaft_radius_property_, "Radius of the arrow's shaft, in meters."); 00325 head_length_property_ = property_manager_->createProperty<FloatProperty>( "Head Length", property_prefix_, boost::bind( &PoseDisplay::getHeadLength, this ), 00326 boost::bind( &PoseDisplay::setHeadLength, this, _1 ), shape_category_, this ); 00327 setPropertyHelpText(head_length_property_, "Length of the arrow's head, in meters."); 00328 head_radius_property_ = property_manager_->createProperty<FloatProperty>( "Head Radius", property_prefix_, boost::bind( &PoseDisplay::getHeadRadius, this ), 00329 boost::bind( &PoseDisplay::setHeadRadius, this, _1 ), shape_category_, this ); 00330 setPropertyHelpText(head_radius_property_, "Radius of the arrow's head, in meters."); 00331 } 00332 break; 00333 case Axes: 00334 axes_length_property_ = property_manager_->createProperty<FloatProperty>( "Axes Length", property_prefix_, boost::bind( &PoseDisplay::getAxesLength, this ), 00335 boost::bind( &PoseDisplay::setAxesLength, this, _1 ), shape_category_, this ); 00336 setPropertyHelpText(axes_length_property_, "Length of each axis, in meters."); 00337 axes_radius_property_ = property_manager_->createProperty<FloatProperty>( "Axes Radius", property_prefix_, boost::bind( &PoseDisplay::getAxesRadius, this ), 00338 boost::bind( &PoseDisplay::setAxesRadius, this, _1 ), shape_category_, this ); 00339 setPropertyHelpText(axes_radius_property_, "Radius of each axis, in meters."); 00340 break; 00341 } 00342 00343 } 00344 00345 void PoseDisplay::createProperties() 00346 { 00347 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PoseDisplay::getTopic, this ), 00348 boost::bind( &PoseDisplay::setTopic, this, _1 ), parent_category_, this ); 00349 setPropertyHelpText(topic_property_, "geometry_msgs::PoseStamped topic to subscribe to."); 00350 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock(); 00351 topic_prop->setMessageType(ros::message_traits::datatype<geometry_msgs::PoseStamped>()); 00352 00353 shape_property_ = property_manager_->createProperty<EnumProperty>( "Shape", property_prefix_, boost::bind( &PoseDisplay::getShape, this ), 00354 boost::bind( &PoseDisplay::setShape, this, _1 ), parent_category_, this ); 00355 setPropertyHelpText(shape_property_, "Shape to display the pose as."); 00356 EnumPropertyPtr enum_prop = shape_property_.lock(); 00357 enum_prop->addOption( "Arrow", Arrow ); 00358 enum_prop->addOption( "Axes", Axes ); 00359 00360 createShapeProperties(); 00361 } 00362 00363 void PoseDisplay::targetFrameChanged() 00364 { 00365 } 00366 00367 void PoseDisplay::fixedFrameChanged() 00368 { 00369 tf_filter_.setTargetFrame( fixed_frame_ ); 00370 clear(); 00371 } 00372 00373 void PoseDisplay::update(float wall_dt, float ros_dt) 00374 { 00375 } 00376 00377 void PoseDisplay::incomingMessage( const geometry_msgs::PoseStamped::ConstPtr& message ) 00378 { 00379 ++messages_received_; 00380 00381 if (!validateFloats(*message)) 00382 { 00383 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); 00384 return; 00385 } 00386 00387 { 00388 std::stringstream ss; 00389 ss << messages_received_ << " messages received"; 00390 setStatus(status_levels::Ok, "Topic", ss.str()); 00391 } 00392 00393 Ogre::Vector3 position; 00394 Ogre::Quaternion orientation; 00395 if (!vis_manager_->getFrameManager()->transform(message->header, message->pose, position, orientation)) 00396 { 00397 ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'", name_.c_str(), message->header.frame_id.c_str(), fixed_frame_.c_str() ); 00398 } 00399 00400 scene_node_->setPosition( position ); 00401 scene_node_->setOrientation( orientation ); 00402 00403 latest_message_ = message; 00404 coll_handler_->setMessage(message); 00405 setVisibility(); 00406 00407 causeRender(); 00408 } 00409 00410 void PoseDisplay::reset() 00411 { 00412 Display::reset(); 00413 clear(); 00414 } 00415 00416 } // namespace rviz