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