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