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_cloud2_display.h"
00031 #include "point_cloud_transformers.h"
00032 #include "rviz/common.h"
00033 #include "rviz/visualization_manager.h"
00034 #include "rviz/properties/property.h"
00035 #include "rviz/properties/property_manager.h"
00036 #include "rviz/frame_manager.h"
00037 #include "rviz/validate_floats.h"
00038
00039 #include <ros/time.h>
00040 #include "ogre_tools/point_cloud.h"
00041
00042 #include <tf/transform_listener.h>
00043
00044 #include <OGRE/OgreSceneNode.h>
00045 #include <OGRE/OgreSceneManager.h>
00046
00047 namespace rviz
00048 {
00049
00050 PointCloud2Display::PointCloud2Display( const std::string& name, VisualizationManager* manager )
00051 : PointCloudBase( name, manager )
00052 , tf_filter_(*manager->getTFClient(), "", 10, threaded_nh_)
00053 {
00054 tf_filter_.connectInput(sub_);
00055 tf_filter_.registerCallback(&PointCloud2Display::incomingCloudCallback, this);
00056 vis_manager_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
00057 }
00058
00059 PointCloud2Display::~PointCloud2Display()
00060 {
00061 unsubscribe();
00062 tf_filter_.clear();
00063 }
00064
00065 void PointCloud2Display::setTopic( const std::string& topic )
00066 {
00067 unsubscribe();
00068 topic_ = topic;
00069 reset();
00070 subscribe();
00071
00072 propertyChanged(topic_property_);
00073
00074 causeRender();
00075 }
00076
00077 void PointCloud2Display::onEnable()
00078 {
00079 PointCloudBase::onEnable();
00080
00081 subscribe();
00082 }
00083
00084 void PointCloud2Display::onDisable()
00085 {
00086 unsubscribe();
00087 tf_filter_.clear();
00088
00089 PointCloudBase::onDisable();
00090 }
00091
00092 void PointCloud2Display::subscribe()
00093 {
00094 if ( !isEnabled() )
00095 {
00096 return;
00097 }
00098
00099 sub_.subscribe(threaded_nh_, topic_, 2);
00100 }
00101
00102 void PointCloud2Display::unsubscribe()
00103 {
00104 sub_.unsubscribe();
00105 }
00106
00107 void PointCloud2Display::incomingCloudCallback(const sensor_msgs::PointCloud2ConstPtr& cloud)
00108 {
00109
00110
00111
00112 sensor_msgs::PointCloud2Ptr filtered(new sensor_msgs::PointCloud2);
00113 int32_t xi = findChannelIndex(cloud, "x");
00114 int32_t yi = findChannelIndex(cloud, "y");
00115 int32_t zi = findChannelIndex(cloud, "z");
00116
00117 if (xi == -1 || yi == -1 || zi == -1)
00118 {
00119 return;
00120 }
00121
00122 const uint32_t xoff = cloud->fields[xi].offset;
00123 const uint32_t yoff = cloud->fields[yi].offset;
00124 const uint32_t zoff = cloud->fields[zi].offset;
00125 const uint8_t type = cloud->fields[xi].datatype;
00126 const uint32_t point_step = cloud->point_step;
00127 const size_t point_count = cloud->width * cloud->height;
00128 filtered->data.resize(cloud->data.size());
00129 if (point_count == 0)
00130 {
00131 return;
00132 }
00133
00134 uint32_t output_count = 0;
00135 const uint8_t* ptr = &cloud->data.front();
00136 for (size_t i = 0; i < point_count; ++i)
00137 {
00138 float x = *reinterpret_cast<const float*>(ptr + xoff);
00139 float y = *reinterpret_cast<const float*>(ptr + yoff);
00140 float z = *reinterpret_cast<const float*>(ptr + zoff);
00141 if (validateFloats(Ogre::Vector3(x, y, z)))
00142 {
00143 memcpy(&filtered->data.front() + (output_count * point_step), ptr, point_step);
00144 ++output_count;
00145 }
00146
00147 ptr += point_step;
00148 }
00149
00150 filtered->header = cloud->header;
00151 filtered->fields = cloud->fields;
00152 filtered->data.resize(output_count * point_step);
00153 filtered->height = 1;
00154 filtered->width = output_count;
00155 filtered->is_bigendian = cloud->is_bigendian;
00156 filtered->point_step = point_step;
00157 filtered->row_step = output_count;
00158
00159 addMessage(filtered);
00160 }
00161
00162 void PointCloud2Display::targetFrameChanged()
00163 {
00164 }
00165
00166 void PointCloud2Display::fixedFrameChanged()
00167 {
00168 tf_filter_.setTargetFrame( fixed_frame_ );
00169
00170 PointCloudBase::fixedFrameChanged();
00171 }
00172
00173 void PointCloud2Display::createProperties()
00174 {
00175 topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Topic", property_prefix_, boost::bind( &PointCloud2Display::getTopic, this ),
00176 boost::bind( &PointCloud2Display::setTopic, this, _1 ), parent_category_, this );
00177 setPropertyHelpText(topic_property_, "sensor_msgs::PointCloud2 topic to subscribe to.");
00178 ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00179 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::PointCloud2>());
00180
00181 PointCloudBase::createProperties();
00182 }
00183
00184 }