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_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/selection/selection_manager.h"
00036 #include "rviz/frame_manager.h"
00037 #include "rviz/validate_floats.h"
00038
00039 #include "ogre_tools/arrow.h"
00040 #include "ogre_tools/axes.h"
00041
00042 #include <tf/transform_listener.h>
00043
00044 #include <boost/bind.hpp>
00045
00046 #include <OGRE/OgreSceneNode.h>
00047 #include <OGRE/OgreSceneManager.h>
00048
00049 namespace rviz
00050 {
00051
00052 class PoseDisplaySelectionHandler : public SelectionHandler
00053 {
00054 public:
00055 PoseDisplaySelectionHandler(const std::string& name)
00056 : name_(name)
00057 {}
00058
00059 void createProperties(const Picked& obj, PropertyManager* property_manager)
00060 {
00061 std::stringstream prefix;
00062 prefix << "Pose " << name_;
00063 CategoryPropertyWPtr cat = property_manager->createCategory(prefix.str(), prefix.str());
00064 properties_.push_back(property_manager->createProperty<StringProperty>("Frame", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getFrame, this), StringProperty::Setter(), cat));
00065 properties_.push_back(property_manager->createProperty<Vector3Property>("Position", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getPosition, this), Vector3Property::Setter(), cat));
00066 properties_.push_back(property_manager->createProperty<QuaternionProperty>("Orientation", prefix.str(), boost::bind(&PoseDisplaySelectionHandler::getOrientation, this), QuaternionProperty::Setter(), cat));
00067 }
00068
00069 void setMessage(const geometry_msgs::PoseStampedConstPtr& message)
00070 {
00071 message_ = message;
00072 }
00073
00074 std::string getFrame()
00075 {
00076 return message_->header.frame_id;
00077 }
00078
00079 Ogre::Vector3 getPosition()
00080 {
00081 return Ogre::Vector3(message_->pose.position.x, message_->pose.position.y, message_->pose.position.z);
00082 }
00083
00084 Ogre::Quaternion getOrientation()
00085 {
00086 return Ogre::Quaternion(message_->pose.orientation.x, message_->pose.orientation.y, message_->pose.orientation.z, message_->pose.orientation.w);
00087 }
00088
00089 private:
00090 std::string name_;
00091 geometry_msgs::PoseStampedConstPtr message_;
00092 };
00093
00094 PoseDisplay::PoseDisplay( const std::string& name, VisualizationManager* manager )
00095 : Display( name, manager )
00096 , color_( 1.0f, 0.1f, 0.0f )
00097 , head_radius_(0.2)
00098 , head_length_(0.3)
00099 , shaft_radius_(0.1)
00100 , shaft_length_(1.0)
00101 , axes_length_(1.0)
00102 , axes_radius_(0.1)
00103 , messages_received_(0)
00104 , tf_filter_(*manager->getTFClient(), "", 5, update_nh_)
00105 {
00106 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00107
00108 tf_filter_.connectInput(sub_);
00109 tf_filter_.registerCallback(boost::bind(&PoseDisplay::incomingMessage, this, _1));
00110 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00111
00112 arrow_ = new ogre_tools::Arrow(scene_manager_, scene_node_, shaft_length_, shaft_radius_, head_length_, head_radius_);
00113
00114 axes_ = new ogre_tools::Axes(scene_manager_, scene_node_, axes_length_, axes_radius_);
00115
00116 setVisibility();
00117
00118 Ogre::Quaternion quat(Ogre::Quaternion::IDENTITY);
00119 robotToOgre(quat);
00120 axes_->setOrientation(quat);
00121
00122 SelectionManager* sel_manager = vis_manager_->getSelectionManager();
00123 coll_handler_.reset(new PoseDisplaySelectionHandler(name_));
00124 coll_ = sel_manager->createCollisionForObject(arrow_, coll_handler_);
00125 sel_manager->createCollisionForObject(axes_, coll_handler_, coll_);
00126
00127 setShape(Arrow);
00128 setAlpha(1.0);
00129 }
00130
00131 PoseDisplay::~PoseDisplay()
00132 {
00133 unsubscribe();
00134
00135 clear();
00136
00137 SelectionManager* sel_manager = vis_manager_->getSelectionManager();
00138 sel_manager->removeObject(coll_);
00139
00140 delete arrow_;
00141 delete axes_;
00142 }
00143
00144 void PoseDisplay::clear()
00145 {
00146 tf_filter_.clear();
00147 latest_message_.reset();
00148 setVisibility();
00149
00150 messages_received_ = 0;
00151 setStatus(status_levels::Warn, "Topic", "No messages received");
00152 }
00153
00154 void PoseDisplay::setTopic( const std::string& topic )
00155 {
00156 unsubscribe();
00157 topic_ = topic;
00158 subscribe();
00159
00160 propertyChanged(topic_property_);
00161
00162 causeRender();
00163 }
00164
00165 void PoseDisplay::setColor( const Color& color )
00166 {
00167 color_ = color;
00168
00169 arrow_->setColor(color.r_, color.g_, color.b_, alpha_);
00170 axes_->setColor(color.r_, color.g_, color.b_, alpha_);
00171
00172 propertyChanged(color_property_);
00173
00174 causeRender();
00175 }
00176
00177 void PoseDisplay::setAlpha( float a )
00178 {
00179 alpha_ = a;
00180
00181 arrow_->setColor(color_.r_, color_.g_, color_.b_, alpha_);
00182 axes_->setColor(color_.r_, color_.g_, color_.b_, alpha_);
00183
00184 propertyChanged(alpha_property_);
00185
00186 causeRender();
00187 }
00188
00189 void PoseDisplay::setHeadRadius(float r)
00190 {
00191 head_radius_ = r;
00192 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_);
00193 propertyChanged(head_radius_property_);
00194 }
00195
00196 void PoseDisplay::setHeadLength(float l)
00197 {
00198 head_length_ = l;
00199 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_);
00200 propertyChanged(head_length_property_);
00201 }
00202
00203 void PoseDisplay::setShaftRadius(float r)
00204 {
00205 shaft_radius_ = r;
00206 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_);
00207 propertyChanged(shaft_radius_property_);
00208 }
00209
00210 void PoseDisplay::setShaftLength(float l)
00211 {
00212 shaft_length_ = l;
00213 arrow_->set(shaft_length_, shaft_radius_, head_length_, head_radius_);
00214 propertyChanged(shaft_length_property_);
00215 }
00216
00217 void PoseDisplay::setAxesRadius(float r)
00218 {
00219 axes_radius_ = r;
00220 axes_->set(axes_length_, axes_radius_);
00221 propertyChanged(axes_radius_property_);
00222 }
00223
00224 void PoseDisplay::setAxesLength(float l)
00225 {
00226 axes_length_ = l;
00227 axes_->set(axes_length_, axes_radius_);
00228 propertyChanged(axes_length_property_);
00229 }
00230
00231 void PoseDisplay::setShape(int shape)
00232 {
00233 current_shape_ = (Shape)shape;
00234
00235 setVisibility();
00236
00237 propertyChanged(shape_property_);
00238
00239 createShapeProperties();
00240
00241 causeRender();
00242 }
00243
00244 void PoseDisplay::setVisibility()
00245 {
00246 arrow_->getSceneNode()->setVisible(false);
00247 axes_->getSceneNode()->setVisible(false);
00248
00249 if (!latest_message_)
00250 {
00251 return;
00252 }
00253
00254 switch (current_shape_)
00255 {
00256 case Arrow:
00257 arrow_->getSceneNode()->setVisible(true);
00258 break;
00259 case Axes:
00260 axes_->getSceneNode()->setVisible(true);
00261 break;
00262 }
00263 }
00264
00265 void PoseDisplay::subscribe()
00266 {
00267 if ( !isEnabled() )
00268 {
00269 return;
00270 }
00271
00272 sub_.subscribe(update_nh_, topic_, 5);
00273 }
00274
00275 void PoseDisplay::unsubscribe()
00276 {
00277 sub_.unsubscribe();
00278 }
00279
00280 void PoseDisplay::onEnable()
00281 {
00282 setVisibility();
00283
00284 subscribe();
00285 }
00286
00287 void PoseDisplay::onDisable()
00288 {
00289 unsubscribe();
00290 clear();
00291 scene_node_->setVisible( false );
00292 }
00293
00294 void PoseDisplay::createShapeProperties()
00295 {
00296 if (!property_manager_)
00297 {
00298 return;
00299 }
00300
00301 property_manager_->deleteProperty(shape_category_.lock());
00302 shape_category_ = property_manager_->createCategory("Shape Properties", property_prefix_, parent_category_, this);
00303
00304 switch (current_shape_)
00305 {
00306 case Arrow:
00307 {
00308 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &PoseDisplay::getColor, this ),
00309 boost::bind( &PoseDisplay::setColor, this, _1 ), shape_category_, this );
00310 setPropertyHelpText(color_property_, "Color to draw the arrow.");
00311 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, boost::bind( &PoseDisplay::getAlpha, this ),
00312 boost::bind( &PoseDisplay::setAlpha, this, _1 ), shape_category_, this );
00313 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the arrow.");
00314 FloatPropertyPtr float_prop = alpha_property_.lock();
00315 float_prop->setMin(0.0);
00316 float_prop->setMax(1.0);
00317
00318 shaft_length_property_ = property_manager_->createProperty<FloatProperty>( "Shaft Length", property_prefix_, boost::bind( &PoseDisplay::getShaftLength, this ),
00319 boost::bind( &PoseDisplay::setShaftLength, this, _1 ), shape_category_, this );
00320 setPropertyHelpText(shaft_length_property_, "Length of the arrow's shaft, in meters.");
00321 shaft_radius_property_ = property_manager_->createProperty<FloatProperty>( "Shaft Radius", property_prefix_, boost::bind( &PoseDisplay::getShaftRadius, this ),
00322 boost::bind( &PoseDisplay::setShaftRadius, this, _1 ), shape_category_, this );
00323 setPropertyHelpText(shaft_radius_property_, "Radius of the arrow's shaft, in meters.");
00324 head_length_property_ = property_manager_->createProperty<FloatProperty>( "Head Length", property_prefix_, boost::bind( &PoseDisplay::getHeadLength, this ),
00325 boost::bind( &PoseDisplay::setHeadLength, this, _1 ), shape_category_, this );
00326 setPropertyHelpText(head_length_property_, "Length of the arrow's head, in meters.");
00327 head_radius_property_ = property_manager_->createProperty<FloatProperty>( "Head Radius", property_prefix_, boost::bind( &PoseDisplay::getHeadRadius, this ),
00328 boost::bind( &PoseDisplay::setHeadRadius, this, _1 ), shape_category_, this );
00329 setPropertyHelpText(head_radius_property_, "Radius of the arrow's head, in meters.");
00330 }
00331 break;
00332 case Axes:
00333 axes_length_property_ = property_manager_->createProperty<FloatProperty>( "Axes Length", property_prefix_, boost::bind( &PoseDisplay::getAxesLength, this ),
00334 boost::bind( &PoseDisplay::setAxesLength, this, _1 ), shape_category_, this );
00335 setPropertyHelpText(axes_length_property_, "Length of each axis, in meters.");
00336 axes_radius_property_ = property_manager_->createProperty<FloatProperty>( "Axes Radius", property_prefix_, boost::bind( &PoseDisplay::getAxesRadius, this ),
00337 boost::bind( &PoseDisplay::setAxesRadius, this, _1 ), shape_category_, this );
00338 setPropertyHelpText(axes_radius_property_, "Radius of each axis, in meters.");
00339 break;
00340 }
00341
00342 }
00343
00344 void PoseDisplay::createProperties()
00345 {
00346 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PoseDisplay::getTopic, this ),
00347 boost::bind( &PoseDisplay::setTopic, this, _1 ), parent_category_, this );
00348 setPropertyHelpText(topic_property_, "geometry_msgs::PoseStamped topic to subscribe to.");
00349 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00350 topic_prop->setMessageType(ros::message_traits::datatype<geometry_msgs::PoseStamped>());
00351
00352 shape_property_ = property_manager_->createProperty<EnumProperty>( "Shape", property_prefix_, boost::bind( &PoseDisplay::getShape, this ),
00353 boost::bind( &PoseDisplay::setShape, this, _1 ), parent_category_, this );
00354 setPropertyHelpText(shape_property_, "Shape to display the pose as.");
00355 EnumPropertyPtr enum_prop = shape_property_.lock();
00356 enum_prop->addOption( "Arrow", Arrow );
00357 enum_prop->addOption( "Axes", Axes );
00358
00359 createShapeProperties();
00360 }
00361
00362 void PoseDisplay::targetFrameChanged()
00363 {
00364 }
00365
00366 void PoseDisplay::fixedFrameChanged()
00367 {
00368 tf_filter_.setTargetFrame( fixed_frame_ );
00369 clear();
00370 }
00371
00372 void PoseDisplay::update(float wall_dt, float ros_dt)
00373 {
00374 }
00375
00376 void PoseDisplay::incomingMessage( const geometry_msgs::PoseStamped::ConstPtr& message )
00377 {
00378 ++messages_received_;
00379
00380 if (!validateFloats(*message))
00381 {
00382 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00383 return;
00384 }
00385
00386 {
00387 std::stringstream ss;
00388 ss << messages_received_ << " messages received";
00389 setStatus(status_levels::Ok, "Topic", ss.str());
00390 }
00391
00392 Ogre::Vector3 position;
00393 Ogre::Quaternion orientation;
00394 if (!vis_manager_->getFrameManager()->transform(message->header, message->pose, position, orientation, true))
00395 {
00396 ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'", name_.c_str(), message->header.frame_id.c_str(), fixed_frame_.c_str() );
00397 }
00398
00399 scene_node_->setPosition( position );
00400 scene_node_->setOrientation( orientation );
00401
00402 latest_message_ = message;
00403 coll_handler_->setMessage(message);
00404 setVisibility();
00405
00406 causeRender();
00407 }
00408
00409 void PoseDisplay::reset()
00410 {
00411 Display::reset();
00412 clear();
00413 }
00414
00415 }