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