00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "grid_cells_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/properties/property.h"
00033 #include "rviz/properties/property_manager.h"
00034 #include "rviz/common.h"
00035 #include "rviz/frame_manager.h"
00036 #include "rviz/validate_floats.h"
00037
00038 #include "ogre_tools/arrow.h"
00039
00040 #include <tf/transform_listener.h>
00041
00042 #include <boost/bind.hpp>
00043
00044 #include <OGRE/OgreSceneNode.h>
00045 #include <OGRE/OgreSceneManager.h>
00046 #include <OGRE/OgreManualObject.h>
00047 #include <OGRE/OgreBillboardSet.h>
00048
00049 #include <ogre_tools/point_cloud.h>
00050
00051 namespace rviz
00052 {
00053
00054 GridCellsDisplay::GridCellsDisplay( const std::string& name, VisualizationManager* manager )
00055 : Display( name, manager )
00056 , color_( 0.1f, 1.0f, 0.0f )
00057 , tf_filter_(*manager->getTFClient(), "", 10, update_nh_)
00058 , messages_received_(0)
00059 {
00060 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00061
00062 static int count = 0;
00063 std::stringstream ss;
00064 ss << "PolyLine" << count++;
00065
00066 cloud_ = new ogre_tools::PointCloud();
00067 cloud_->setRenderMode( ogre_tools::PointCloud::RM_BILLBOARDS_COMMON_FACING );
00068 cloud_->setCommonDirection( Ogre::Vector3::UNIT_Y );
00069 cloud_->setCommonUpVector( Ogre::Vector3::NEGATIVE_UNIT_Z );
00070 scene_node_->attachObject(cloud_);
00071 setAlpha( 1.0f );
00072
00073 tf_filter_.connectInput(sub_);
00074 tf_filter_.registerCallback(boost::bind(&GridCellsDisplay::incomingMessage, this, _1));
00075 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00076 }
00077
00078 GridCellsDisplay::~GridCellsDisplay()
00079 {
00080 unsubscribe();
00081 clear();
00082
00083 scene_manager_->destroySceneNode(scene_node_->getName());
00084 delete cloud_;
00085 }
00086
00087 void GridCellsDisplay::clear()
00088 {
00089 cloud_->clear();
00090
00091 messages_received_ = 0;
00092 setStatus(status_levels::Warn, "Topic", "No messages received");
00093 }
00094
00095 void GridCellsDisplay::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 GridCellsDisplay::setColor( const Color& color )
00109 {
00110 color_ = color;
00111
00112 propertyChanged(color_property_);
00113
00114 processMessage(current_message_);
00115 causeRender();
00116 }
00117
00118 void GridCellsDisplay::setAlpha( float alpha )
00119 {
00120 alpha_ = alpha;
00121
00122 cloud_->setAlpha( alpha );
00123
00124 propertyChanged(alpha_property_);
00125
00126 processMessage(current_message_);
00127 causeRender();
00128 }
00129
00130 void GridCellsDisplay::subscribe()
00131 {
00132 if ( !isEnabled() )
00133 {
00134 return;
00135 }
00136
00137 sub_.subscribe(update_nh_, topic_, 10);
00138 }
00139
00140 void GridCellsDisplay::unsubscribe()
00141 {
00142 sub_.unsubscribe();
00143 }
00144
00145 void GridCellsDisplay::onEnable()
00146 {
00147 scene_node_->setVisible( true );
00148 subscribe();
00149 }
00150
00151 void GridCellsDisplay::onDisable()
00152 {
00153 unsubscribe();
00154 clear();
00155 scene_node_->setVisible( false );
00156 }
00157
00158 void GridCellsDisplay::fixedFrameChanged()
00159 {
00160 clear();
00161
00162 tf_filter_.setTargetFrame( fixed_frame_ );
00163 }
00164
00165 void GridCellsDisplay::update(float wall_dt, float ros_dt)
00166 {
00167 }
00168
00169 bool validateFloats(const nav_msgs::GridCells& msg)
00170 {
00171 bool valid = true;
00172 valid = valid && validateFloats(msg.cell_width);
00173 valid = valid && validateFloats(msg.cell_height);
00174 valid = valid && validateFloats(msg.cells);
00175 return valid;
00176 }
00177
00178 void GridCellsDisplay::processMessage(const nav_msgs::GridCells::ConstPtr& msg)
00179 {
00180 if (!msg)
00181 {
00182 return;
00183 }
00184
00185 cloud_->clear();
00186
00187 ++messages_received_;
00188
00189 if (!validateFloats(*msg))
00190 {
00191 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00192 return;
00193 }
00194
00195 std::stringstream ss;
00196 ss << messages_received_ << " messages received";
00197 setStatus(status_levels::Ok, "Topic", ss.str());
00198
00199 Ogre::Vector3 position;
00200 Ogre::Quaternion orientation;
00201 if (!vis_manager_->getFrameManager()->getTransform(msg->header, position, orientation, true))
00202 {
00203 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() );
00204 }
00205
00206 scene_node_->setPosition( position );
00207 scene_node_->setOrientation( orientation );
00208
00209 Ogre::ColourValue color( color_.r_, color_.g_, color_.b_, alpha_ );
00210
00211 cloud_->setDimensions(msg->cell_width, msg->cell_height, 0.0);
00212
00213 uint32_t num_points = msg->cells.size();
00214
00215 typedef std::vector< ogre_tools::PointCloud::Point > V_Point;
00216 V_Point points;
00217 points.resize( num_points );
00218 for(uint32_t i = 0; i < num_points; i++)
00219 {
00220 ogre_tools::PointCloud::Point& current_point = points[ i ];
00221
00222 Ogre::Vector3 pos(msg->cells[i].x, msg->cells[i].y, msg->cells[i].z);
00223 robotToOgre(pos);
00224
00225 current_point.x = pos.x;
00226 current_point.y = pos.y;
00227 current_point.z = pos.z;
00228 current_point.setColor(color.r, color.g, color.b);
00229 }
00230
00231 cloud_->clear();
00232
00233 if ( !points.empty() )
00234 {
00235 cloud_->addPoints( &points.front(), points.size() );
00236 }
00237 }
00238
00239 void GridCellsDisplay::incomingMessage(const nav_msgs::GridCells::ConstPtr& msg)
00240 {
00241 processMessage(msg);
00242 }
00243
00244 void GridCellsDisplay::reset()
00245 {
00246 Display::reset();
00247 clear();
00248 }
00249
00250 void GridCellsDisplay::createProperties()
00251 {
00252 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &GridCellsDisplay::getColor, this ),
00253 boost::bind( &GridCellsDisplay::setColor, this, _1 ), parent_category_, this );
00254 setPropertyHelpText(color_property_, "Color of the grid cells.");
00255 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &GridCellsDisplay::getAlpha, this ),
00256 boost::bind( &GridCellsDisplay::setAlpha, this, _1 ), parent_category_, this );
00257 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the cells.");
00258
00259 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &GridCellsDisplay::getTopic, this ),
00260 boost::bind( &GridCellsDisplay::setTopic, this, _1 ), parent_category_, this );
00261 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00262 topic_prop->setMessageType(ros::message_traits::datatype<nav_msgs::GridCells>());
00263 setPropertyHelpText(topic_property_, "nav_msgs::GridCells topic to subscribe to.");
00264 }
00265
00266 const char* GridCellsDisplay::getDescription()
00267 {
00268 return "Displays data from a nav_msgs::GridCells message as either points or lines.";
00269 }
00270
00271 }
00272