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