range_display.cpp
Go to the documentation of this file.
00001 #include "range_display.h"
00002 #include "rviz/visualization_manager.h"
00003 #include "rviz/properties/property.h"
00004 #include "rviz/properties/property_manager.h"
00005 #include "rviz/frame_manager.h"
00006 #include "rviz/validate_floats.h"
00007 
00008 #include <tf/transform_listener.h>
00009 
00010 #include <ogre_tools/shape.h>
00011 
00012 #include <OGRE/OgreSceneNode.h>
00013 #include <OGRE/OgreSceneManager.h>
00014 
00015 namespace rviz
00016 {
00017 RangeDisplay::RangeDisplay()
00018   : Display()
00019   , color_( 1.0f, 1.0f, 1.0f )
00020   , messages_received_(0)
00021 {
00022 }
00023 
00024 void RangeDisplay::onInitialize()
00025 {
00026   tf_filter_ = new tf::MessageFilter<sensor_msgs::Range>(*vis_manager_->getTFClient(), "", 10, update_nh_);
00027 
00028   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00029   scene_node_->setVisible( false );
00030   
00031   setBuffer( 1 );
00032   Ogre::Vector3 scale( 0, 0, 0);
00033 
00034   tf_filter_->connectInput(sub_);
00035   tf_filter_->registerCallback(boost::bind(&RangeDisplay::incomingMessage, this, _1));
00036   vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00037   setAlpha( 0.5f );
00038 }
00039 
00040 RangeDisplay::~RangeDisplay()
00041 {
00042   unsubscribe();
00043   clear();
00044   for (size_t i = 0; i < cones_.size(); i++) {
00045     delete cones_[i];
00046   }
00047 
00048   delete tf_filter_;
00049 }
00050 
00051 void RangeDisplay::clear()
00052 {
00053   setBuffer( cones_.size() );
00054   tf_filter_->clear();
00055   messages_received_ = 0;
00056   setStatus(rviz::status_levels::Warn, "Topic", "No messages received");
00057 }
00058 
00059 void RangeDisplay::setTopic( const std::string& topic )
00060 {
00061   unsubscribe();
00062 
00063   topic_ = topic;
00064 
00065   subscribe();
00066 
00067   propertyChanged(topic_property_);
00068 
00069   causeRender();
00070 }
00071 
00072 void RangeDisplay::setColor( const rviz::Color& color )
00073 {
00074   color_ = color;
00075 
00076   propertyChanged(color_property_);
00077 
00078   processMessage(current_message_);
00079   causeRender();
00080 }
00081 
00082 void RangeDisplay::setBuffer( int buffer )
00083 {
00084   if(buffer < 1)
00085     buffer = 1;
00086   buffer_len_ = buffer;
00087 
00088   propertyChanged(bufferLen_property_);
00089   
00090   for (size_t i = 0; i < cones_.size(); i++) {
00091     delete cones_[i];
00092   }
00093   cones_.resize(buffer_len_);
00094   for (size_t i = 0; i < cones_.size(); i++) {
00095     cones_[i] = new ogre_tools::Shape(ogre_tools::Shape::Cone, vis_manager_->getSceneManager(), scene_node_);
00096     ogre_tools::Shape* cone = cones_[i];
00097     
00098     Ogre::Vector3 position;
00099     Ogre::Quaternion orientation;
00100     geometry_msgs::Pose pose;
00101     pose.position.z = pose.position.y = 0;
00102     pose.position.x = 0;
00103     pose.orientation.x = 0;
00104     pose.orientation.z = 0;
00105     cone->setPosition(position);
00106     cone->setOrientation(orientation); 
00107     Ogre::Vector3 scale( 0, 0, 0);
00108     cone->setScale(scale);
00109     cone->setColor(color_.r_, color_.g_, color_.b_, 0);
00110     
00111   }
00112   
00113 }
00114 
00115 void RangeDisplay::setAlpha( float alpha )
00116 {
00117   alpha_ = alpha;
00118 
00119   propertyChanged(alpha_property_);
00120 
00121   processMessage(current_message_);
00122   causeRender();
00123 }
00124 
00125 void RangeDisplay::subscribe()
00126 {
00127   if ( !isEnabled() )
00128   {
00129     return;
00130   }
00131 
00132   sub_.subscribe(update_nh_, topic_, 10);
00133 }
00134 
00135 void RangeDisplay::unsubscribe()
00136 {
00137   sub_.unsubscribe();
00138 }
00139 
00140 void RangeDisplay::onEnable()
00141 {
00142   scene_node_->setVisible( true );
00143   subscribe();
00144 }
00145 
00146 void RangeDisplay::onDisable()
00147 {
00148   unsubscribe();
00149   clear();
00150   scene_node_->setVisible( false );
00151 }
00152 
00153 void RangeDisplay::fixedFrameChanged()
00154 {
00155   tf_filter_->setTargetFrame( fixed_frame_ );
00156   clear();
00157 }
00158 
00159 void RangeDisplay::update(float wall_dt, float ros_dt)
00160 {
00161 }
00162 
00163 
00164 void RangeDisplay::processMessage(const sensor_msgs::Range::ConstPtr& msg)
00165 {
00166   if (!msg)
00167   {
00168     return;
00169   }
00170 
00171   ++messages_received_;
00172   
00173   ogre_tools::Shape* cone = cones_[messages_received_ % buffer_len_];
00174 
00175   {
00176     std::stringstream ss;
00177     ss << messages_received_ << " messages received";
00178     setStatus(rviz::status_levels::Ok, "Topic", ss.str());
00179   }
00180 
00181   Ogre::Vector3 position;
00182   Ogre::Quaternion orientation;
00183   geometry_msgs::Pose pose;
00184   pose.position.z = pose.position.y = 0;
00185   pose.position.x = msg->range/2 - .008824 * msg->range; // .008824 fudge factor measured, must be inaccuracy of cone model.
00186   pose.orientation.z = 0.707;
00187   pose.orientation.w = 0.707;
00188   if( !vis_manager_->getFrameManager()->transform( msg->header.frame_id, msg->header.stamp, pose, position, orientation ))
00189   {
00190     ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() );
00191   }
00192 
00193   cone->setPosition(position);
00194   cone->setOrientation(orientation); 
00195 
00196   double cone_width = 2.0 * msg->range * tan( msg->field_of_view / 2.0 );
00197   Ogre::Vector3 scale( cone_width, msg->range, cone_width );
00198   cone->setScale(scale);
00199   cone->setColor(color_.r_, color_.g_, color_.b_, alpha_);
00200 
00201 }
00202 
00203 void RangeDisplay::incomingMessage(const sensor_msgs::Range::ConstPtr& msg)
00204 {
00205   processMessage(msg);
00206 }
00207 
00208 void RangeDisplay::reset()
00209 {
00210   Display::reset();
00211   clear();
00212 }
00213 
00214 void RangeDisplay::createProperties()
00215 {
00216   topic_property_ = property_manager_->createProperty<rviz::ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &RangeDisplay::getTopic, this ),
00217                                                                                 boost::bind( &RangeDisplay::setTopic, this, _1 ), parent_category_, this );
00218   setPropertyHelpText(topic_property_, "sensor_msgs::Range topic to subscribe to.");
00219   rviz::ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00220   topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::Range>());
00221   color_property_ = property_manager_->createProperty<rviz::ColorProperty>( "Color", property_prefix_, boost::bind( &RangeDisplay::getColor, this ),
00222                                                                       boost::bind( &RangeDisplay::setColor, this, _1 ), parent_category_, this );
00223   setPropertyHelpText(color_property_, "Color to draw the range.");
00224   alpha_property_ = property_manager_->createProperty<rviz::FloatProperty>( "Alpha", property_prefix_, boost::bind( &RangeDisplay::getAlpha, this ),
00225                                                                        boost::bind( &RangeDisplay::setAlpha, this, _1 ), parent_category_, this );
00226   setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the range.");
00227   bufferLen_property_ = property_manager_->createProperty<rviz::IntProperty>( "Buffer Length", property_prefix_, boost::bind( &RangeDisplay::getBuffer, this ),
00228                                                                        boost::bind( &RangeDisplay::setBuffer, this, _1 ), parent_category_, this );
00229   setPropertyHelpText(bufferLen_property_, "Number of prior measurements to display.");
00230   
00231 }
00232 
00233 const char* RangeDisplay::getDescription()
00234 {
00235   return "Displays data from a sensor_msgs::Range message as a cone.";
00236 }
00237 } // namespace rviz


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:53