Go to the documentation of this file.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 "point_cloud_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
00036 #include <ros/time.h>
00037 #include "ogre_tools/point_cloud.h"
00038
00039 #include <tf/transform_listener.h>
00040
00041 #include <OGRE/OgreSceneNode.h>
00042 #include <OGRE/OgreSceneManager.h>
00043
00044 namespace rviz
00045 {
00046
00047 PointCloudDisplay::PointCloudDisplay()
00048 : PointCloudBase()
00049 , tf_filter_( 0 )
00050 {
00051 }
00052
00053 PointCloudDisplay::~PointCloudDisplay()
00054 {
00055 unsubscribe();
00056 tf_filter_->clear();
00057 delete tf_filter_;
00058 }
00059
00060 void PointCloudDisplay::onInitialize()
00061 {
00062 PointCloudBase::onInitialize();
00063 tf_filter_ = new tf::MessageFilter<sensor_msgs::PointCloud>( *vis_manager_->getTFClient(), "", 10, threaded_nh_ );
00064 tf_filter_->connectInput(sub_);
00065 tf_filter_->registerCallback(&PointCloudDisplay::incomingCloudCallback, this);
00066 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00067 }
00068
00069 void PointCloudDisplay::setTopic( const std::string& topic )
00070 {
00071 unsubscribe();
00072 topic_ = topic;
00073 reset();
00074 subscribe();
00075
00076 propertyChanged(topic_property_);
00077
00078 causeRender();
00079 }
00080
00081 void PointCloudDisplay::onEnable()
00082 {
00083 PointCloudBase::onEnable();
00084
00085 subscribe();
00086 }
00087
00088 void PointCloudDisplay::onDisable()
00089 {
00090 unsubscribe();
00091 tf_filter_->clear();
00092
00093 PointCloudBase::onDisable();
00094 }
00095
00096 void PointCloudDisplay::subscribe()
00097 {
00098 if ( !isEnabled() )
00099 {
00100 return;
00101 }
00102
00103 sub_.subscribe(threaded_nh_, topic_, 2);
00104 }
00105
00106 void PointCloudDisplay::unsubscribe()
00107 {
00108 sub_.unsubscribe();
00109 }
00110
00111 void PointCloudDisplay::incomingCloudCallback(const sensor_msgs::PointCloudConstPtr& cloud)
00112 {
00113 addMessage(cloud);
00114 }
00115
00116 void PointCloudDisplay::targetFrameChanged()
00117 {
00118 }
00119
00120 void PointCloudDisplay::fixedFrameChanged()
00121 {
00122 tf_filter_->setTargetFrame( fixed_frame_ );
00123
00124 PointCloudBase::fixedFrameChanged();
00125 }
00126
00127 void PointCloudDisplay::createProperties()
00128 {
00129 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PointCloudDisplay::getTopic, this ),
00130 boost::bind( &PointCloudDisplay::setTopic, this, _1 ), parent_category_, this );
00131 setPropertyHelpText(topic_property_, "sensor_msgs::PointCloud topic to subscribe to.");
00132 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00133 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::PointCloud>());
00134
00135 PointCloudBase::createProperties();
00136 }
00137
00138 }