00001 #include "range_display.h"
00002 #include "rviz/visualization_manager.h"
00003 #include "rviz/properties/property.h"
00004 #include "rviz/properties/property_manager.h"
00005 #include "rviz/frame_manager.h"
00006 #include "rviz/validate_floats.h"
00007
00008 #include <tf/transform_listener.h>
00009
00010 #include <ogre_tools/shape.h>
00011
00012 #include <OGRE/OgreSceneNode.h>
00013 #include <OGRE/OgreSceneManager.h>
00014
00015 namespace rviz
00016 {
00017 RangeDisplay::RangeDisplay( const std::string& name, rviz::VisualizationManager* manager )
00018 : Display( name, manager )
00019 , color_( 1.0f, 1.0f, 1.0f )
00020 , messages_received_(0)
00021 , tf_filter_(*manager->getTFClient(), "", 10, update_nh_)
00022 {
00023 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00024 scene_node_->setVisible( false );
00025
00026 setBuffer( 1 );
00027 Ogre::Vector3 scale( 0, 0, 0);
00028
00029 tf_filter_.connectInput(sub_);
00030 tf_filter_.registerCallback(boost::bind(&RangeDisplay::incomingMessage, this, _1));
00031 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00032 setAlpha( 0.5f );
00033 }
00034
00035 RangeDisplay::~RangeDisplay()
00036 {
00037 unsubscribe();
00038 clear();
00039 for (size_t i = 0; i < cones_.size(); i++) {
00040 delete cones_[i];
00041 }
00042 }
00043
00044 void RangeDisplay::clear()
00045 {
00046 setBuffer( cones_.size() );
00047 tf_filter_.clear();
00048 messages_received_ = 0;
00049 setStatus(rviz::status_levels::Warn, "Topic", "No messages received");
00050 }
00051
00052 void RangeDisplay::setTopic( const std::string& topic )
00053 {
00054 unsubscribe();
00055
00056 topic_ = topic;
00057
00058 subscribe();
00059
00060 propertyChanged(topic_property_);
00061
00062 causeRender();
00063 }
00064
00065 void RangeDisplay::setColor( const rviz::Color& color )
00066 {
00067 color_ = color;
00068
00069 propertyChanged(color_property_);
00070
00071 processMessage(current_message_);
00072 causeRender();
00073 }
00074
00075 void RangeDisplay::setBuffer( int buffer )
00076 {
00077 if(buffer < 1)
00078 buffer = 1;
00079 buffer_len_ = buffer;
00080
00081 propertyChanged(bufferLen_property_);
00082
00083 for (size_t i = 0; i < cones_.size(); i++) {
00084 delete cones_[i];
00085 }
00086 cones_.resize(buffer_len_);
00087 for (size_t i = 0; i < cones_.size(); i++) {
00088 cones_[i] = new ogre_tools::Shape(ogre_tools::Shape::Cone, vis_manager_->getSceneManager(), scene_node_);
00089 ogre_tools::Shape* cone = cones_[i];
00090
00091 Ogre::Vector3 position;
00092 Ogre::Quaternion orientation;
00093 geometry_msgs::Pose pose;
00094 pose.position.z = pose.position.y = 0;
00095 pose.position.x = 0;
00096 pose.orientation.x = 0;
00097 pose.orientation.z = 0;
00098 cone->setPosition(position);
00099 cone->setOrientation(orientation);
00100 Ogre::Vector3 scale( 0, 0, 0);
00101 cone->setScale(scale);
00102 cone->setColor(color_.r_, color_.g_, color_.b_, 0);
00103
00104 }
00105
00106 }
00107
00108 void RangeDisplay::setAlpha( float alpha )
00109 {
00110 alpha_ = alpha;
00111
00112 propertyChanged(alpha_property_);
00113
00114 processMessage(current_message_);
00115 causeRender();
00116 }
00117
00118 void RangeDisplay::subscribe()
00119 {
00120 if ( !isEnabled() )
00121 {
00122 return;
00123 }
00124
00125 sub_.subscribe(update_nh_, topic_, 10);
00126 }
00127
00128 void RangeDisplay::unsubscribe()
00129 {
00130 sub_.unsubscribe();
00131 }
00132
00133 void RangeDisplay::onEnable()
00134 {
00135 scene_node_->setVisible( true );
00136 subscribe();
00137 }
00138
00139 void RangeDisplay::onDisable()
00140 {
00141 unsubscribe();
00142 clear();
00143 scene_node_->setVisible( false );
00144 }
00145
00146 void RangeDisplay::fixedFrameChanged()
00147 {
00148 tf_filter_.setTargetFrame( fixed_frame_ );
00149 clear();
00150 }
00151
00152 void RangeDisplay::update(float wall_dt, float ros_dt)
00153 {
00154 }
00155
00156
00157 void RangeDisplay::processMessage(const sensor_msgs::Range::ConstPtr& msg)
00158 {
00159 if (!msg)
00160 {
00161 return;
00162 }
00163
00164 ++messages_received_;
00165
00166 ogre_tools::Shape* cone = cones_[messages_received_ % buffer_len_];
00167
00168 {
00169 std::stringstream ss;
00170 ss << messages_received_ << " messages received";
00171 setStatus(rviz::status_levels::Ok, "Topic", ss.str());
00172 }
00173
00174 Ogre::Vector3 position;
00175 Ogre::Quaternion orientation;
00176 geometry_msgs::Pose pose;
00177 pose.position.z = pose.position.y = 0;
00178 pose.position.x = msg->range/2 - .008824 * msg->range;
00179 pose.orientation.z = 0.707;
00180 pose.orientation.w = 0.707;
00181 if( !vis_manager_->getFrameManager()->transform( msg->header.frame_id, msg->header.stamp, pose, position, orientation ))
00182 {
00183 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), fixed_frame_.c_str() );
00184 }
00185
00186 cone->setPosition(position);
00187 cone->setOrientation(orientation);
00188
00189 double cone_width = 2.0 * msg->range * tan( msg->field_of_view / 2.0 );
00190 Ogre::Vector3 scale( cone_width, msg->range, cone_width );
00191 cone->setScale(scale);
00192 cone->setColor(color_.r_, color_.g_, color_.b_, alpha_);
00193
00194 }
00195
00196 void RangeDisplay::incomingMessage(const sensor_msgs::Range::ConstPtr& msg)
00197 {
00198 processMessage(msg);
00199 }
00200
00201 void RangeDisplay::reset()
00202 {
00203 Display::reset();
00204 clear();
00205 }
00206
00207 void RangeDisplay::createProperties()
00208 {
00209 topic_property_ = property_manager_->createProperty<rviz::ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &RangeDisplay::getTopic, this ),
00210 boost::bind( &RangeDisplay::setTopic, this, _1 ), parent_category_, this );
00211 setPropertyHelpText(topic_property_, "sensor_msgs::Range topic to subscribe to.");
00212 rviz::ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00213 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::Range>());
00214 color_property_ = property_manager_->createProperty<rviz::ColorProperty>( "Color", property_prefix_, boost::bind( &RangeDisplay::getColor, this ),
00215 boost::bind( &RangeDisplay::setColor, this, _1 ), parent_category_, this );
00216 setPropertyHelpText(color_property_, "Color to draw the range.");
00217 alpha_property_ = property_manager_->createProperty<rviz::FloatProperty>( "Alpha", property_prefix_, boost::bind( &RangeDisplay::getAlpha, this ),
00218 boost::bind( &RangeDisplay::setAlpha, this, _1 ), parent_category_, this );
00219 setPropertyHelpText(alpha_property_, "Amount of transparency to apply to the range.");
00220 bufferLen_property_ = property_manager_->createProperty<rviz::IntProperty>( "Buffer Length", property_prefix_, boost::bind( &RangeDisplay::getBuffer, this ),
00221 boost::bind( &RangeDisplay::setBuffer, this, _1 ), parent_category_, this );
00222 setPropertyHelpText(bufferLen_property_, "Number of prior measurements to display.");
00223
00224 }
00225
00226 const char* RangeDisplay::getDescription()
00227 {
00228 return "Displays data from a sensor_msgs::Range message as a cone.";
00229 }
00230 }