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