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 "pose_array_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 "ogre_tools/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
00047 namespace rviz
00048 {
00049
00050 PoseArrayDisplay::PoseArrayDisplay( const std::string& name, VisualizationManager* manager )
00051 : Display( name, manager )
00052 , color_( 1.0f, 0.1f, 0.0f )
00053 , messages_received_(0)
00054 , tf_filter_(*manager->getTFClient(), "", 2, update_nh_)
00055 {
00056 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00057
00058 static int count = 0;
00059 std::stringstream ss;
00060 ss << "ParticleCloud2D" << count++;
00061 manual_object_ = scene_manager_->createManualObject( ss.str() );
00062 manual_object_->setDynamic( true );
00063 scene_node_->attachObject( manual_object_ );
00064
00065 tf_filter_.connectInput(sub_);
00066 tf_filter_.registerCallback(boost::bind(&PoseArrayDisplay::incomingMessage, this, _1));
00067 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00068 }
00069
00070 PoseArrayDisplay::~PoseArrayDisplay()
00071 {
00072 unsubscribe();
00073 clear();
00074
00075 scene_manager_->destroyManualObject( manual_object_ );
00076 }
00077
00078 void PoseArrayDisplay::clear()
00079 {
00080 manual_object_->clear();
00081
00082 messages_received_ = 0;
00083 setStatus(status_levels::Warn, "Topic", "No messages received");
00084 }
00085
00086 void PoseArrayDisplay::setTopic( const std::string& topic )
00087 {
00088 unsubscribe();
00089
00090 topic_ = topic;
00091
00092 subscribe();
00093
00094 propertyChanged(topic_property_);
00095
00096 causeRender();
00097 }
00098
00099 void PoseArrayDisplay::setColor( const Color& color )
00100 {
00101 color_ = color;
00102
00103 propertyChanged(color_property_);
00104
00105 causeRender();
00106 }
00107
00108 void PoseArrayDisplay::subscribe()
00109 {
00110 if ( !isEnabled() )
00111 {
00112 return;
00113 }
00114
00115 sub_.subscribe(update_nh_, topic_, 5);
00116 }
00117
00118 void PoseArrayDisplay::unsubscribe()
00119 {
00120 sub_.unsubscribe();
00121 }
00122
00123 void PoseArrayDisplay::onEnable()
00124 {
00125 scene_node_->setVisible( true );
00126 subscribe();
00127 }
00128
00129 void PoseArrayDisplay::onDisable()
00130 {
00131 unsubscribe();
00132 clear();
00133 scene_node_->setVisible( false );
00134 }
00135
00136 void PoseArrayDisplay::createProperties()
00137 {
00138 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PoseArrayDisplay::getTopic, this ),
00139 boost::bind( &PoseArrayDisplay::setTopic, this, _1 ), parent_category_, this );
00140 setPropertyHelpText(topic_property_, "geometry_msgs::PoseArray topic to subscribe to.");
00141 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00142 topic_prop->setMessageType(ros::message_traits::datatype<geometry_msgs::PoseArray>());
00143
00144 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &PoseArrayDisplay::getColor, this ),
00145 boost::bind( &PoseArrayDisplay::setColor, this, _1 ), parent_category_, this );
00146 setPropertyHelpText(color_property_, "Color to draw the arrows.");
00147 }
00148
00149 void PoseArrayDisplay::fixedFrameChanged()
00150 {
00151 clear();
00152 tf_filter_.setTargetFrame( fixed_frame_ );
00153 }
00154
00155 void PoseArrayDisplay::update(float wall_dt, float ros_dt)
00156 {
00157 }
00158
00159 bool validateFloats(const geometry_msgs::PoseArray& msg)
00160 {
00161 return validateFloats(msg.poses);
00162 }
00163
00164 void PoseArrayDisplay::processMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
00165 {
00166 ++messages_received_;
00167
00168 if (!validateFloats(*msg))
00169 {
00170 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00171 return;
00172 }
00173
00174 {
00175 std::stringstream ss;
00176 ss << messages_received_ << " messages received";
00177 setStatus(status_levels::Ok, "Topic", ss.str());
00178 }
00179
00180 manual_object_->clear();
00181
00182 Ogre::Vector3 position;
00183 Ogre::Quaternion orientation;
00184 if (!vis_manager_->getFrameManager()->getTransform(msg->header, position, orientation))
00185 {
00186 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() );
00187 }
00188
00189 scene_node_->setPosition( position );
00190 scene_node_->setOrientation( orientation );
00191
00192 manual_object_->clear();
00193
00194 Ogre::ColourValue color( color_.r_, color_.g_, color_.b_, 1.0f );
00195 size_t num_poses = msg->poses.size();
00196 manual_object_->estimateVertexCount( num_poses * 6 );
00197 manual_object_->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST );
00198 for( size_t i=0; i < num_poses; ++i)
00199 {
00200 Ogre::Vector3 pos(msg->poses[i].position.x, msg->poses[i].position.y, msg->poses[i].position.z);
00201 tf::Quaternion quat;
00202 tf::quaternionMsgToTF(msg->poses[i].orientation, quat);
00203 Ogre::Quaternion orient = Ogre::Quaternion::IDENTITY;
00204 orient = Ogre::Quaternion( quat.w(), quat.x(), quat.y(), quat.z() ) * orient;
00205
00206 const static float radius = 0.3f;
00207 Ogre::Vector3 vertices[6];
00208 vertices[0] = pos;
00209 vertices[1] = pos + orient * Ogre::Vector3(radius, 0, 0);
00210 vertices[2] = vertices[1];
00211 vertices[3] = pos + orient * Ogre::Vector3(0.75*radius, 0.2*radius, 0);
00212 vertices[4] = vertices[1];
00213 vertices[5] = pos + orient * Ogre::Vector3(0.75*radius, -0.2*radius, 0);
00214
00215 for ( int i = 0; i < 6; ++i )
00216 {
00217 manual_object_->position( vertices[i] );
00218 manual_object_->colour( color );
00219 }
00220 }
00221 manual_object_->end();
00222
00223 causeRender();
00224 }
00225
00226 void PoseArrayDisplay::incomingMessage(const geometry_msgs::PoseArray::ConstPtr& msg)
00227 {
00228 processMessage(msg);
00229 }
00230
00231 void PoseArrayDisplay::reset()
00232 {
00233 Display::reset();
00234 clear();
00235 }
00236
00237 }
00238