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