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 "odometry_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
00047 namespace rviz
00048 {
00049
00050 OdometryDisplay::OdometryDisplay( const std::string& name, VisualizationManager* manager )
00051 : Display( name, manager )
00052 , color_( 1.0f, 0.1f, 0.0f )
00053 , keep_(100)
00054 , position_tolerance_( 0.1 )
00055 , angle_tolerance_( 0.1 )
00056 , messages_received_(0)
00057 , tf_filter_(*manager->getTFClient(), "", 5, update_nh_)
00058 {
00059 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00060
00061 tf_filter_.connectInput(sub_);
00062 tf_filter_.registerCallback(boost::bind(&OdometryDisplay::incomingMessage, this, _1));
00063 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00064 }
00065
00066 OdometryDisplay::~OdometryDisplay()
00067 {
00068 unsubscribe();
00069
00070 clear();
00071 }
00072
00073 void OdometryDisplay::clear()
00074 {
00075 D_Arrow::iterator it = arrows_.begin();
00076 D_Arrow::iterator end = arrows_.end();
00077 for ( ; it != end; ++it )
00078 {
00079 delete *it;
00080 }
00081 arrows_.clear();
00082
00083 if (last_used_message_)
00084 {
00085 last_used_message_.reset();
00086 }
00087
00088 tf_filter_.clear();
00089
00090 messages_received_ = 0;
00091 setStatus(status_levels::Warn, "Topic", "No messages received");
00092 }
00093
00094 void OdometryDisplay::setTopic( const std::string& topic )
00095 {
00096 unsubscribe();
00097 topic_ = topic;
00098 clear();
00099 subscribe();
00100
00101 propertyChanged(topic_property_);
00102
00103 causeRender();
00104 }
00105
00106 void OdometryDisplay::setColor( const Color& color )
00107 {
00108 color_ = color;
00109
00110 D_Arrow::iterator it = arrows_.begin();
00111 D_Arrow::iterator end = arrows_.end();
00112 for ( ; it != end; ++it )
00113 {
00114 ogre_tools::Arrow* arrow = *it;
00115 arrow->setColor( color.r_, color.g_, color.b_, 1.0f );
00116 }
00117
00118 propertyChanged(color_property_);
00119
00120 causeRender();
00121 }
00122
00123 void OdometryDisplay::setKeep(uint32_t keep)
00124 {
00125 keep_ = keep;
00126
00127 propertyChanged(keep_property_);
00128 }
00129
00130 void OdometryDisplay::setPositionTolerance( float tol )
00131 {
00132 position_tolerance_ = tol;
00133
00134 propertyChanged(position_tolerance_property_);
00135 }
00136
00137 void OdometryDisplay::setAngleTolerance( float tol )
00138 {
00139 angle_tolerance_ = tol;
00140
00141 propertyChanged(angle_tolerance_property_);
00142 }
00143
00144 void OdometryDisplay::subscribe()
00145 {
00146 if ( !isEnabled() )
00147 {
00148 return;
00149 }
00150
00151 sub_.subscribe(update_nh_, topic_, 5);
00152 }
00153
00154 void OdometryDisplay::unsubscribe()
00155 {
00156 sub_.unsubscribe();
00157 }
00158
00159 void OdometryDisplay::onEnable()
00160 {
00161 scene_node_->setVisible( true );
00162 subscribe();
00163 }
00164
00165 void OdometryDisplay::onDisable()
00166 {
00167 unsubscribe();
00168 clear();
00169 scene_node_->setVisible( false );
00170 }
00171
00172 void OdometryDisplay::createProperties()
00173 {
00174 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &OdometryDisplay::getTopic, this ),
00175 boost::bind( &OdometryDisplay::setTopic, this, _1 ), parent_category_, this );
00176 setPropertyHelpText(topic_property_, "nav_msgs::Odometry topic to subscribe to.");
00177 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00178 topic_prop->setMessageType(ros::message_traits::datatype<nav_msgs::Odometry>());
00179
00180 color_property_ = property_manager_->createProperty<ColorProperty>( "Color", property_prefix_, boost::bind( &OdometryDisplay::getColor, this ),
00181 boost::bind( &OdometryDisplay::setColor, this, _1 ), parent_category_, this );
00182 setPropertyHelpText(color_property_, "Color of the arrows.");
00183
00184 position_tolerance_property_ = property_manager_->createProperty<FloatProperty>( "Position Tolerance", property_prefix_, boost::bind( &OdometryDisplay::getPositionTolerance, this ),
00185 boost::bind( &OdometryDisplay::setPositionTolerance, this, _1 ), parent_category_, this );
00186 setPropertyHelpText(position_tolerance_property_, "Distance, in meters from the last arrow dropped, that will cause a new arrow to drop.");
00187 angle_tolerance_property_ = property_manager_->createProperty<FloatProperty>( "Angle Tolerance", property_prefix_, boost::bind( &OdometryDisplay::getAngleTolerance, this ),
00188 boost::bind( &OdometryDisplay::setAngleTolerance, this, _1 ), parent_category_, this );
00189 setPropertyHelpText(angle_tolerance_property_, "Angular distance from the last arrow dropped, that will cause a new arrow to drop.");
00190
00191 keep_property_ = property_manager_->createProperty<IntProperty>( "Keep", property_prefix_, boost::bind( &OdometryDisplay::getKeep, this ),
00192 boost::bind( &OdometryDisplay::setKeep, this, _1 ), parent_category_, this );
00193 setPropertyHelpText(keep_property_, "Number of arrows to keep before removing the oldest.");
00194 }
00195
00196 bool validateFloats(const nav_msgs::Odometry& msg)
00197 {
00198 bool valid = true;
00199 valid = valid && validateFloats(msg.pose.pose);
00200 valid = valid && validateFloats(msg.twist.twist);
00201 return valid;
00202 }
00203
00204 void OdometryDisplay::processMessage( const nav_msgs::Odometry::ConstPtr& message )
00205 {
00206 ++messages_received_;
00207
00208 if (!validateFloats(*message))
00209 {
00210 setStatus(status_levels::Error, "Topic", "Message contained invalid floating point values (nans or infs)");
00211 return;
00212 }
00213
00214 {
00215 std::stringstream ss;
00216 ss << messages_received_ << " messages received";
00217 setStatus(status_levels::Ok, "Topic", ss.str());
00218 }
00219
00220 if ( last_used_message_ )
00221 {
00222 Ogre::Vector3 last_position(last_used_message_->pose.pose.position.x, last_used_message_->pose.pose.position.y, last_used_message_->pose.pose.position.z);
00223 Ogre::Vector3 current_position(message->pose.pose.position.x, message->pose.pose.position.y, message->pose.pose.position.z);
00224 Ogre::Quaternion last_orientation(last_used_message_->pose.pose.orientation.w, last_used_message_->pose.pose.orientation.x, last_used_message_->pose.pose.orientation.y, last_used_message_->pose.pose.orientation.z);
00225 Ogre::Quaternion current_orientation(message->pose.pose.orientation.w, message->pose.pose.orientation.x, message->pose.pose.orientation.y, message->pose.pose.orientation.z);
00226
00227 if ((last_position - current_position).length() < position_tolerance_ && (last_orientation - current_orientation).normalise() < angle_tolerance_)
00228 {
00229 return;
00230 }
00231 }
00232
00233 ogre_tools::Arrow* arrow = new ogre_tools::Arrow( scene_manager_, scene_node_, 0.8f, 0.05f, 0.2f, 0.2f );
00234
00235 transformArrow( message, arrow );
00236
00237 arrow->setColor( color_.r_, color_.g_, color_.b_, 1.0f );
00238 arrow->setUserData( Ogre::Any((void*)this) );
00239
00240 arrows_.push_back( arrow );
00241 last_used_message_ = message;
00242 }
00243
00244 void OdometryDisplay::transformArrow( const nav_msgs::Odometry::ConstPtr& message, ogre_tools::Arrow* arrow )
00245 {
00246 Ogre::Vector3 position;
00247 Ogre::Quaternion orientation;
00248 if (!vis_manager_->getFrameManager()->transform(message->header, message->pose.pose, position, orientation, true))
00249 {
00250 ROS_ERROR( "Error transforming odometry '%s' from frame '%s' to frame '%s'", name_.c_str(), message->header.frame_id.c_str(), fixed_frame_.c_str() );
00251 }
00252
00253 arrow->setPosition( position );
00254 arrow->setOrientation( orientation );
00255 }
00256
00257 void OdometryDisplay::targetFrameChanged()
00258 {
00259 }
00260
00261 void OdometryDisplay::fixedFrameChanged()
00262 {
00263 tf_filter_.setTargetFrame( fixed_frame_ );
00264 clear();
00265 }
00266
00267 void OdometryDisplay::update(float wall_dt, float ros_dt)
00268 {
00269 if (keep_ > 0)
00270 {
00271 while (arrows_.size() > keep_)
00272 {
00273 delete arrows_.front();
00274 arrows_.pop_front();
00275 }
00276 }
00277 }
00278
00279 void OdometryDisplay::incomingMessage( const nav_msgs::Odometry::ConstPtr& message )
00280 {
00281 processMessage(message);
00282 causeRender();
00283 }
00284
00285 void OdometryDisplay::reset()
00286 {
00287 Display::reset();
00288
00289 clear();
00290 }
00291
00292 }