$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include <pluginlib/class_loader.h> 00031 00032 #include "point_cloud_base.h" 00033 #include "point_cloud_transformer.h" 00034 #include "point_cloud_transformers.h" 00035 #include "rviz/visualization_manager.h" 00036 #include "rviz/selection/selection_manager.h" 00037 #include "rviz/properties/property.h" 00038 #include "rviz/properties/property_manager.h" 00039 #include "rviz/validate_floats.h" 00040 #include "rviz/frame_manager.h" 00041 00042 #include <ros/time.h> 00043 #include "ogre_tools/point_cloud.h" 00044 00045 #include <tf/transform_listener.h> 00046 00047 #include <OGRE/OgreSceneNode.h> 00048 #include <OGRE/OgreSceneManager.h> 00049 #include <OGRE/OgreWireBoundingBox.h> 00050 00051 namespace rviz 00052 { 00053 00054 template<typename T> 00055 T getValue(const T& val) 00056 { 00057 return val; 00058 } 00059 00060 class PointCloudSelectionHandler : public SelectionHandler 00061 { 00062 public: 00063 PointCloudSelectionHandler(PointCloudBase* display); 00064 virtual ~PointCloudSelectionHandler(); 00065 00066 virtual void createProperties(const Picked& obj, PropertyManager* property_manager); 00067 virtual void destroyProperties(const Picked& obj, PropertyManager* property_manager); 00068 00069 virtual bool needsAdditionalRenderPass(uint32_t pass) 00070 { 00071 if (pass < 2) 00072 { 00073 return true; 00074 } 00075 00076 return false; 00077 } 00078 00079 virtual void preRenderPass(uint32_t pass); 00080 virtual void postRenderPass(uint32_t pass); 00081 00082 virtual void onSelect(const Picked& obj); 00083 virtual void onDeselect(const Picked& obj); 00084 00085 virtual void getAABBs(const Picked& obj, V_AABB& aabbs); 00086 00087 private: 00088 void getCloudAndLocalIndexByGlobalIndex(int global_index, PointCloudBase::CloudInfoPtr& cloud_out, int& index_out); 00089 00090 PointCloudBase* display_; 00091 }; 00092 00093 PointCloudSelectionHandler::PointCloudSelectionHandler(PointCloudBase* display) 00094 : display_(display) 00095 { 00096 } 00097 00098 PointCloudSelectionHandler::~PointCloudSelectionHandler() 00099 { 00100 } 00101 00102 void PointCloudSelectionHandler::preRenderPass(uint32_t pass) 00103 { 00104 SelectionHandler::preRenderPass(pass); 00105 00106 if (pass == 1) 00107 { 00108 display_->cloud_->setColorByIndex(true); 00109 } 00110 } 00111 00112 void PointCloudSelectionHandler::postRenderPass(uint32_t pass) 00113 { 00114 SelectionHandler::postRenderPass(pass); 00115 00116 if (pass == 1) 00117 { 00118 display_->cloud_->setColorByIndex(false); 00119 } 00120 } 00121 00122 void PointCloudSelectionHandler::getCloudAndLocalIndexByGlobalIndex(int global_index, PointCloudBase::CloudInfoPtr& cloud_out, int& index_out) 00123 { 00124 boost::mutex::scoped_lock lock(display_->clouds_mutex_); 00125 00126 int count = 0; 00127 00128 PointCloudBase::D_CloudInfo::iterator cloud_it = display_->clouds_.begin(); 00129 PointCloudBase::D_CloudInfo::iterator cloud_end = display_->clouds_.end(); 00130 for (;cloud_it != cloud_end; ++cloud_it) 00131 { 00132 const PointCloudBase::CloudInfoPtr& info = *cloud_it; 00133 00134 if (global_index < count + (int)info->num_points_) 00135 { 00136 index_out = global_index - count; 00137 cloud_out = info; 00138 00139 return; 00140 } 00141 00142 count += info->message_->width * info->message_->height; 00143 } 00144 } 00145 00146 Ogre::Vector3 pointFromCloud(const sensor_msgs::PointCloud2ConstPtr& cloud, uint32_t index) 00147 { 00148 int32_t xi = findChannelIndex(cloud, "x"); 00149 int32_t yi = findChannelIndex(cloud, "y"); 00150 int32_t zi = findChannelIndex(cloud, "z"); 00151 00152 const uint32_t xoff = cloud->fields[xi].offset; 00153 const uint32_t yoff = cloud->fields[yi].offset; 00154 const uint32_t zoff = cloud->fields[zi].offset; 00155 const uint8_t type = cloud->fields[xi].datatype; 00156 const uint32_t point_step = cloud->point_step; 00157 float x = valueFromCloud<float>(cloud, xoff, type, point_step, index); 00158 float y = valueFromCloud<float>(cloud, yoff, type, point_step, index); 00159 float z = valueFromCloud<float>(cloud, zoff, type, point_step, index); 00160 return Ogre::Vector3(x, y, z); 00161 } 00162 00163 void PointCloudSelectionHandler::createProperties(const Picked& obj, PropertyManager* property_manager) 00164 { 00165 typedef std::set<int> S_int; 00166 S_int indices; 00167 { 00168 S_uint64::const_iterator it = obj.extra_handles.begin(); 00169 S_uint64::const_iterator end = obj.extra_handles.end(); 00170 for (; it != end; ++it) 00171 { 00172 uint64_t handle = *it; 00173 indices.insert((handle & 0xffffffff) - 1); 00174 } 00175 } 00176 00177 { 00178 S_int::iterator it = indices.begin(); 00179 S_int::iterator end = indices.end(); 00180 for (; it != end; ++it) 00181 { 00182 int global_index = *it; 00183 int index = 0; 00184 PointCloudBase::CloudInfoPtr cloud; 00185 00186 getCloudAndLocalIndexByGlobalIndex(global_index, cloud, index); 00187 00188 if (!cloud) 00189 { 00190 continue; 00191 } 00192 00193 const sensor_msgs::PointCloud2ConstPtr& message = cloud->message_; 00194 00195 std::stringstream prefix; 00196 prefix << "Point " << index << " [cloud " << message.get() << "]"; 00197 00198 if (property_manager->hasProperty(prefix.str(), "")) 00199 { 00200 continue; 00201 } 00202 00203 CategoryPropertyWPtr cat = property_manager->createCategory(prefix.str(), ""); 00204 00205 // Do xyz first, from the transformed xyz 00206 { 00207 std::stringstream ss; 00208 ss << "Position"; 00209 Ogre::Vector3 pos(cloud->transformed_points_.points[index].position); 00210 property_manager->createProperty<Vector3Property>(ss.str(), prefix.str(), boost::bind(getValue<Ogre::Vector3>, pos), Vector3Property::Setter(), cat); 00211 } 00212 00213 for (size_t field = 0; field < message->fields.size(); ++field) 00214 { 00215 const sensor_msgs::PointField& f = message->fields[field]; 00216 const std::string& name = f.name; 00217 00218 if (name == "x" || name == "y" || name == "z" || name == "X" || name == "Y" || name == "Z") 00219 { 00220 continue; 00221 } 00222 00223 float val = valueFromCloud<float>(message, f.offset, f.datatype, message->point_step, index); 00224 00225 std::stringstream ss; 00226 ss << field << ": " << name; 00227 property_manager->createProperty<FloatProperty>(ss.str(), prefix.str(), boost::bind(getValue<float>, val), FloatProperty::Setter(), cat); 00228 } 00229 } 00230 } 00231 } 00232 00233 void PointCloudSelectionHandler::destroyProperties(const Picked& obj, PropertyManager* property_manager) 00234 { 00235 typedef std::set<int> S_int; 00236 S_int indices; 00237 { 00238 S_uint64::const_iterator it = obj.extra_handles.begin(); 00239 S_uint64::const_iterator end = obj.extra_handles.end(); 00240 for (; it != end; ++it) 00241 { 00242 uint64_t handle = *it; 00243 indices.insert((handle & 0xffffffff) - 1); 00244 } 00245 } 00246 00247 { 00248 S_int::iterator it = indices.begin(); 00249 S_int::iterator end = indices.end(); 00250 for (; it != end; ++it) 00251 { 00252 int global_index = *it; 00253 int index = 0; 00254 PointCloudBase::CloudInfoPtr cloud; 00255 00256 getCloudAndLocalIndexByGlobalIndex(global_index, cloud, index); 00257 00258 if (!cloud) 00259 { 00260 continue; 00261 } 00262 00263 const sensor_msgs::PointCloud2ConstPtr& message = cloud->message_; 00264 00265 std::stringstream prefix; 00266 prefix << "Point " << index << " [cloud " << message.get() << "]"; 00267 00268 if (property_manager->hasProperty(prefix.str(), "")) 00269 { 00270 property_manager->deleteProperty(prefix.str(), ""); 00271 } 00272 } 00273 } 00274 } 00275 00276 void PointCloudSelectionHandler::getAABBs(const Picked& obj, V_AABB& aabbs) 00277 { 00278 S_uint64::iterator it = obj.extra_handles.begin(); 00279 S_uint64::iterator end = obj.extra_handles.end(); 00280 for (; it != end; ++it) 00281 { 00282 M_HandleToBox::iterator find_it = boxes_.find(std::make_pair(obj.handle, *it - 1)); 00283 if (find_it != boxes_.end()) 00284 { 00285 Ogre::WireBoundingBox* box = find_it->second.second; 00286 00287 aabbs.push_back(box->getWorldBoundingBox()); 00288 } 00289 } 00290 } 00291 00292 void PointCloudSelectionHandler::onSelect(const Picked& obj) 00293 { 00294 S_uint64::iterator it = obj.extra_handles.begin(); 00295 S_uint64::iterator end = obj.extra_handles.end(); 00296 for (; it != end; ++it) 00297 { 00298 int global_index = (*it & 0xffffffff) - 1; 00299 00300 int index = 0; 00301 PointCloudBase::CloudInfoPtr cloud; 00302 00303 getCloudAndLocalIndexByGlobalIndex(global_index, cloud, index); 00304 00305 if (!cloud) 00306 { 00307 continue; 00308 } 00309 00310 sensor_msgs::PointCloud2ConstPtr message = cloud->message_; 00311 00312 Ogre::Vector3 pos = cloud->transform_ * pointFromCloud(message, index); 00313 00314 float size = 0.002; 00315 if (display_->style_ != PointCloudBase::Points) 00316 { 00317 size = display_->billboard_size_ / 2.0; 00318 } 00319 00320 Ogre::AxisAlignedBox aabb(pos - size, pos + size); 00321 00322 createBox(std::make_pair(obj.handle, global_index), aabb, "RVIZ/Cyan"); 00323 } 00324 } 00325 00326 void PointCloudSelectionHandler::onDeselect(const Picked& obj) 00327 { 00328 S_uint64::iterator it = obj.extra_handles.begin(); 00329 S_uint64::iterator end = obj.extra_handles.end(); 00330 for (; it != end; ++it) 00331 { 00332 int global_index = (*it & 0xffffffff) - 1; 00333 00334 destroyBox(std::make_pair(obj.handle, global_index)); 00335 } 00336 } 00337 00338 PointCloudBase::CloudInfo::CloudInfo() 00339 : time_(0.0f) 00340 , transform_(Ogre::Matrix4::ZERO) 00341 , num_points_(0) 00342 {} 00343 00344 PointCloudBase::CloudInfo::~CloudInfo() 00345 { 00346 } 00347 00348 PointCloudBase::PointCloudBase() 00349 : Display() 00350 , spinner_(1, &cbqueue_) 00351 , new_cloud_(false) 00352 , new_xyz_transformer_(false) 00353 , new_color_transformer_(false) 00354 , needs_retransform_(false) 00355 , style_( Billboards ) 00356 , billboard_size_( 0.01 ) 00357 , point_decay_time_(0.0f) 00358 , selectable_(false) 00359 , coll_handle_(0) 00360 , messages_received_(0) 00361 , total_point_count_(0) 00362 , transformer_class_loader_( new pluginlib::ClassLoader<PointCloudTransformer>( "rviz_qt", "rviz::PointCloudTransformer" )) 00363 { 00364 cloud_ = new ogre_tools::PointCloud(); 00365 } 00366 00367 void PointCloudBase::onInitialize() 00368 { 00369 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00370 scene_node_->attachObject(cloud_); 00371 coll_handler_ = PointCloudSelectionHandlerPtr(new PointCloudSelectionHandler(this)); 00372 00373 setStyle( style_ ); 00374 setBillboardSize( billboard_size_ ); 00375 setAlpha(1.0f); 00376 00377 setSelectable(true); 00378 00379 loadTransformers(); 00380 00381 threaded_nh_.setCallbackQueue(&cbqueue_); 00382 spinner_.start(); 00383 } 00384 00385 void deleteProperties(PropertyManager* man, V_PropertyBaseWPtr& props) 00386 { 00387 V_PropertyBaseWPtr::iterator prop_it = props.begin(); 00388 V_PropertyBaseWPtr::iterator prop_end = props.end(); 00389 for (; prop_it != prop_end; ++prop_it) 00390 { 00391 man->deleteProperty(prop_it->lock()); 00392 } 00393 00394 props.clear(); 00395 } 00396 00397 PointCloudBase::~PointCloudBase() 00398 { 00399 spinner_.stop(); 00400 00401 if (coll_handle_) 00402 { 00403 SelectionManager* sel_manager = vis_manager_->getSelectionManager(); 00404 sel_manager->removeObject(coll_handle_); 00405 } 00406 00407 scene_manager_->destroySceneNode(scene_node_->getName()); 00408 delete cloud_; 00409 00410 if (property_manager_) 00411 { 00412 M_TransformerInfo::iterator it = transformers_.begin(); 00413 M_TransformerInfo::iterator end = transformers_.end(); 00414 for (; it != end; ++it) 00415 { 00416 deleteProperties( property_manager_, it->second.xyz_props ); 00417 deleteProperties( property_manager_, it->second.color_props ); 00418 } 00419 } 00420 00421 delete transformer_class_loader_; 00422 } 00423 00424 void PointCloudBase::loadTransformers() 00425 { 00426 std::vector<std::string> classes = transformer_class_loader_->getDeclaredClasses(); 00427 std::vector<std::string>::iterator ci; 00428 00429 for( ci = classes.begin(); ci != classes.end(); ci++ ) 00430 { 00431 const std::string& lookup_name = *ci; 00432 std::string name = transformer_class_loader_->getName( lookup_name ); 00433 00434 if( transformers_.count( name ) > 0 ) 00435 { 00436 ROS_ERROR( "Transformer type [%s] is already loaded.", name.c_str() ); 00437 continue; 00438 } 00439 00440 PointCloudTransformerPtr trans( transformer_class_loader_->createClassInstance( lookup_name, true )); 00441 trans->init( boost::bind( &PointCloudBase::causeRetransform, this )); 00442 TransformerInfo info; 00443 info.transformer = trans; 00444 info.readable_name = name; 00445 info.lookup_name = lookup_name; 00446 transformers_[ name ] = info; 00447 00448 if( property_manager_ ) 00449 { 00450 info.transformer->createProperties( property_manager_, parent_category_, 00451 property_prefix_ + "." + name, 00452 PointCloudTransformer::Support_XYZ, info.xyz_props ); 00453 info.transformer->createProperties( property_manager_, parent_category_, 00454 property_prefix_ + "." + name, 00455 PointCloudTransformer::Support_Color, info.color_props ); 00456 } 00457 } 00458 } 00459 00460 void PointCloudBase::setAlpha( float alpha ) 00461 { 00462 alpha_ = alpha; 00463 00464 cloud_->setAlpha(alpha_); 00465 00466 propertyChanged(alpha_property_); 00467 } 00468 00469 void PointCloudBase::setSelectable( bool selectable ) 00470 { 00471 if (selectable_ != selectable) 00472 { 00473 SelectionManager* sel_manager = vis_manager_->getSelectionManager(); 00474 00475 if (selectable) 00476 { 00477 coll_handle_ = sel_manager->createHandle(); 00478 00479 sel_manager->addObject(coll_handle_, coll_handler_); 00480 00481 // Break out coll handle into r/g/b/a floats 00482 float r = ((coll_handle_ >> 16) & 0xff) / 255.0f; 00483 float g = ((coll_handle_ >> 8) & 0xff) / 255.0f; 00484 float b = (coll_handle_ & 0xff) / 255.0f; 00485 Ogre::ColourValue col(r, g, b, 1.0f); 00486 cloud_->setPickColor(col); 00487 } 00488 else 00489 { 00490 sel_manager->removeObject(coll_handle_); 00491 coll_handle_ = 0; 00492 cloud_->setPickColor(Ogre::ColourValue(0.0f, 0.0f, 0.0f, 0.0f)); 00493 } 00494 } 00495 00496 selectable_ = selectable; 00497 00498 propertyChanged(selectable_property_); 00499 } 00500 00501 void PointCloudBase::setDecayTime( float time ) 00502 { 00503 point_decay_time_ = time; 00504 00505 propertyChanged(decay_time_property_); 00506 00507 causeRender(); 00508 } 00509 00510 void PointCloudBase::setStyle( int style ) 00511 { 00512 ROS_ASSERT( style < StyleCount ); 00513 00514 style_ = style; 00515 00516 ogre_tools::PointCloud::RenderMode mode = ogre_tools::PointCloud::RM_POINTS; 00517 if (style == Billboards) 00518 { 00519 mode = ogre_tools::PointCloud::RM_BILLBOARDS; 00520 } 00521 else if (style == BillboardSpheres) 00522 { 00523 mode = ogre_tools::PointCloud::RM_BILLBOARD_SPHERES; 00524 } 00525 else if (style == Boxes) 00526 { 00527 mode = ogre_tools::PointCloud::RM_BOXES; 00528 } 00529 00530 if (style == Points) 00531 { 00532 hideProperty( billboard_size_property_ ); 00533 } 00534 else 00535 { 00536 showProperty( billboard_size_property_ ); 00537 } 00538 00539 cloud_->setRenderMode(mode); 00540 00541 propertyChanged(style_property_); 00542 00543 causeRender(); 00544 } 00545 00546 void PointCloudBase::setBillboardSize( float size ) 00547 { 00548 billboard_size_ = size; 00549 00550 cloud_->setDimensions( size, size, size ); 00551 00552 propertyChanged(billboard_size_property_); 00553 00554 causeRender(); 00555 } 00556 00557 void PointCloudBase::onEnable() 00558 { 00559 } 00560 00561 void PointCloudBase::onDisable() 00562 { 00563 clouds_.clear(); 00564 cloud_->clear(); 00565 messages_received_ = 0; 00566 total_point_count_ = 0; 00567 } 00568 00569 void PointCloudBase::causeRetransform() 00570 { 00571 boost::mutex::scoped_lock lock(clouds_mutex_); 00572 needs_retransform_ = true; 00573 } 00574 00575 void PointCloudBase::update(float wall_dt, float ros_dt) 00576 { 00577 { 00578 boost::mutex::scoped_lock lock(clouds_mutex_); 00579 00580 if (needs_retransform_) 00581 { 00582 retransform(); 00583 needs_retransform_ = false; 00584 } 00585 00586 D_CloudInfo::iterator cloud_it = clouds_.begin(); 00587 D_CloudInfo::iterator cloud_end = clouds_.end(); 00588 for (;cloud_it != cloud_end; ++cloud_it) 00589 { 00590 const CloudInfoPtr& info = *cloud_it; 00591 00592 info->time_ += ros_dt; 00593 } 00594 00595 if (point_decay_time_ > 0.0f) 00596 { 00597 bool removed = false; 00598 uint32_t points_to_pop = 0; 00599 while (!clouds_.empty() && clouds_.front()->time_ > point_decay_time_) 00600 { 00601 total_point_count_ -= clouds_.front()->num_points_; 00602 points_to_pop += clouds_.front()->num_points_; 00603 clouds_.pop_front(); 00604 removed = true; 00605 } 00606 00607 if (removed) 00608 { 00609 cloud_->popPoints(points_to_pop); 00610 causeRender(); 00611 } 00612 } 00613 } 00614 00615 if (new_cloud_) 00616 { 00617 boost::mutex::scoped_lock lock(new_clouds_mutex_); 00618 00619 if (point_decay_time_ == 0.0f) 00620 { 00621 clouds_.clear(); 00622 cloud_->clear(); 00623 00624 ROS_ASSERT(!new_points_.empty()); 00625 ROS_ASSERT(!new_clouds_.empty()); 00626 V_Point& points = new_points_.back(); 00627 cloud_->addPoints(&points.front(), points.size()); 00628 clouds_.push_back(new_clouds_.back()); 00629 00630 total_point_count_ = points.size(); 00631 } 00632 else 00633 { 00634 { 00635 VV_Point::iterator it = new_points_.begin(); 00636 VV_Point::iterator end = new_points_.end(); 00637 for (; it != end; ++it) 00638 { 00639 V_Point& points = *it; 00640 total_point_count_ += points.size(); 00641 cloud_->addPoints( &points.front(), points.size() ); 00642 } 00643 } 00644 00645 { 00646 V_CloudInfo::iterator it = new_clouds_.begin(); 00647 V_CloudInfo::iterator end = new_clouds_.end(); 00648 for (; it != end; ++it) 00649 { 00650 clouds_.push_back(*it); 00651 } 00652 } 00653 } 00654 00655 new_clouds_.clear(); 00656 new_points_.clear(); 00657 new_cloud_ = false; 00658 } 00659 00660 { 00661 boost::recursive_mutex::scoped_try_lock lock( transformers_mutex_ ); 00662 00663 if( lock.owns_lock() ) 00664 { 00665 if( new_xyz_transformer_ || new_color_transformer_ ) 00666 { 00667 M_TransformerInfo::iterator it = transformers_.begin(); 00668 M_TransformerInfo::iterator end = transformers_.end(); 00669 for (; it != end; ++it) 00670 { 00671 const std::string& name = it->first; 00672 TransformerInfo& info = it->second; 00673 00674 if( name == getXYZTransformer() ) 00675 { 00676 std::for_each( info.xyz_props.begin(), info.xyz_props.end(), showProperty<PropertyBase> ); 00677 } 00678 else 00679 { 00680 std::for_each( info.xyz_props.begin(), info.xyz_props.end(), hideProperty<PropertyBase> ); 00681 } 00682 00683 if( name == getColorTransformer() ) 00684 { 00685 std::for_each( info.color_props.begin(), info.color_props.end(), showProperty<PropertyBase> ); 00686 } 00687 else 00688 { 00689 std::for_each( info.color_props.begin(), info.color_props.end(), hideProperty<PropertyBase> ); 00690 } 00691 } 00692 } 00693 } 00694 00695 new_xyz_transformer_ = false; 00696 new_color_transformer_ = false; 00697 } 00698 00699 updateStatus(); 00700 } 00701 00702 void PointCloudBase::updateTransformers(const sensor_msgs::PointCloud2ConstPtr& cloud, bool fully_update) 00703 { 00704 EditEnumPropertyPtr xyz_prop = xyz_transformer_property_.lock(); 00705 if (xyz_prop) 00706 { 00707 xyz_prop->clear(); 00708 } 00709 00710 EditEnumPropertyPtr color_prop = color_transformer_property_.lock(); 00711 if (color_prop) 00712 { 00713 color_prop->clear(); 00714 } 00715 00716 // Get the channels that we could potentially render 00717 std::string xyz_name = getXYZTransformer(); 00718 std::string color_name = getColorTransformer(); 00719 00720 typedef std::set<std::pair<uint8_t, std::string> > S_string; 00721 S_string valid_xyz, valid_color; 00722 bool cur_xyz_valid = false; 00723 bool cur_color_valid = false; 00724 M_TransformerInfo::iterator trans_it = transformers_.begin(); 00725 M_TransformerInfo::iterator trans_end = transformers_.end(); 00726 for(;trans_it != trans_end; ++trans_it) 00727 { 00728 const std::string& name = trans_it->first; 00729 const PointCloudTransformerPtr& trans = trans_it->second.transformer; 00730 uint32_t mask = trans->supports(cloud); 00731 if (mask & PointCloudTransformer::Support_XYZ) 00732 { 00733 valid_xyz.insert(std::make_pair(trans->score(cloud), name)); 00734 if (name == xyz_name) 00735 { 00736 cur_xyz_valid = true; 00737 } 00738 00739 if (xyz_prop) 00740 { 00741 xyz_prop->addOption(name); 00742 } 00743 } 00744 00745 if (mask & PointCloudTransformer::Support_Color) 00746 { 00747 valid_color.insert(std::make_pair(trans->score(cloud), name)); 00748 00749 if (name == color_name) 00750 { 00751 cur_color_valid = true; 00752 } 00753 00754 if (color_prop) 00755 { 00756 color_prop->addOption(name); 00757 } 00758 } 00759 } 00760 00761 if (!cur_xyz_valid) 00762 { 00763 if (!valid_xyz.empty()) 00764 { 00765 if (fully_update) 00766 { 00767 setXYZTransformer(valid_xyz.rbegin()->second); 00768 } 00769 else 00770 { 00771 xyz_transformer_ = valid_xyz.rbegin()->second; 00772 } 00773 } 00774 } 00775 00776 if (!cur_color_valid) 00777 { 00778 if (!valid_color.empty()) 00779 { 00780 if (fully_update) 00781 { 00782 setColorTransformer(valid_color.rbegin()->second); 00783 } 00784 else 00785 { 00786 color_transformer_ = valid_color.rbegin()->second; 00787 } 00788 } 00789 } 00790 00791 if (xyz_prop) 00792 { 00793 xyz_prop->changed(); 00794 } 00795 00796 if (color_prop) 00797 { 00798 color_prop->changed(); 00799 } 00800 } 00801 00802 void PointCloudBase::updateStatus() 00803 { 00804 if (messages_received_ == 0) 00805 { 00806 setStatus(status_levels::Warn, "Topic", "No messages received"); 00807 } 00808 else 00809 { 00810 std::stringstream ss; 00811 ss << messages_received_ << " messages received"; 00812 setStatus(status_levels::Ok, "Topic", ss.str()); 00813 } 00814 00815 { 00816 std::stringstream ss; 00817 ss << "Showing [" << total_point_count_ << "] points from [" << clouds_.size() << "] messages"; 00818 setStatus(status_levels::Ok, "Points", ss.str()); 00819 } 00820 } 00821 00822 void PointCloudBase::processMessage(const sensor_msgs::PointCloud2ConstPtr& cloud) 00823 { 00824 CloudInfoPtr info(new CloudInfo); 00825 info->message_ = cloud; 00826 info->time_ = 0; 00827 00828 V_Point points; 00829 if (transformCloud(info, points, true)) 00830 { 00831 boost::mutex::scoped_lock lock(new_clouds_mutex_); 00832 00833 new_clouds_.push_back(info); 00834 new_points_.push_back(V_Point()); 00835 new_points_.back().swap(points); 00836 00837 new_cloud_ = true; 00838 } 00839 } 00840 00841 void PointCloudBase::setXYZTransformer(const std::string& name) 00842 { 00843 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00844 if (xyz_transformer_ == name) 00845 { 00846 return; 00847 } 00848 00849 if (transformers_.count(name) == 0) 00850 { 00851 return; 00852 } 00853 00854 xyz_transformer_ = name; 00855 new_xyz_transformer_ = true; 00856 propertyChanged(xyz_transformer_property_); 00857 00858 causeRetransform(); 00859 } 00860 00861 void PointCloudBase::setColorTransformer(const std::string& name) 00862 { 00863 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00864 if (color_transformer_ == name) 00865 { 00866 return; 00867 } 00868 00869 if (transformers_.count(name) == 0) 00870 { 00871 return; 00872 } 00873 00874 color_transformer_ = name; 00875 new_color_transformer_ = true; 00876 propertyChanged(color_transformer_property_); 00877 00878 causeRetransform(); 00879 } 00880 00881 PointCloudTransformerPtr PointCloudBase::getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud) 00882 { 00883 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00884 M_TransformerInfo::iterator it = transformers_.find(xyz_transformer_); 00885 if (it != transformers_.end()) 00886 { 00887 const PointCloudTransformerPtr& trans = it->second.transformer; 00888 if (trans->supports(cloud) & PointCloudTransformer::Support_XYZ) 00889 { 00890 return trans; 00891 } 00892 } 00893 00894 return PointCloudTransformerPtr(); 00895 } 00896 00897 PointCloudTransformerPtr PointCloudBase::getColorTransformer(const sensor_msgs::PointCloud2ConstPtr& cloud) 00898 { 00899 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00900 M_TransformerInfo::iterator it = transformers_.find(color_transformer_); 00901 if (it != transformers_.end()) 00902 { 00903 const PointCloudTransformerPtr& trans = it->second.transformer; 00904 if (trans->supports(cloud) & PointCloudTransformer::Support_Color) 00905 { 00906 return trans; 00907 } 00908 } 00909 00910 return PointCloudTransformerPtr(); 00911 } 00912 00913 void PointCloudBase::retransform() 00914 { 00915 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00916 00917 cloud_->clear(); 00918 00919 // transformCloud can change the transformers, store them off so we can reset them afterwards 00920 std::string xyz_trans = xyz_transformer_; 00921 std::string color_trans = color_transformer_; 00922 00923 D_CloudInfo::iterator it = clouds_.begin(); 00924 D_CloudInfo::iterator end = clouds_.end(); 00925 for (; it != end; ++it) 00926 { 00927 const CloudInfoPtr& cloud = *it; 00928 V_Point points; 00929 transformCloud(cloud, points, false); 00930 if (!points.empty()) 00931 { 00932 cloud_->addPoints(&points.front(), points.size()); 00933 } 00934 } 00935 00936 xyz_transformer_ = xyz_trans; 00937 color_transformer_ = color_trans; 00938 } 00939 00940 bool PointCloudBase::transformCloud(const CloudInfoPtr& info, V_Point& points, bool fully_update_transformers) 00941 { 00942 Ogre::Matrix4 transform = info->transform_; 00943 00944 if (transform == Ogre::Matrix4::ZERO) 00945 { 00946 Ogre::Vector3 pos; 00947 Ogre::Quaternion orient; 00948 if (!vis_manager_->getFrameManager()->getTransform(info->message_->header, pos, orient)) 00949 { 00950 std::stringstream ss; 00951 ss << "Failed to transform from frame [" << info->message_->header.frame_id << "] to frame [" << vis_manager_->getFrameManager()->getFixedFrame() << "]"; 00952 setStatus(status_levels::Error, "Message", ss.str()); 00953 return false; 00954 } 00955 00956 transform = Ogre::Matrix4(orient); 00957 transform.setTrans(pos); 00958 info->transform_ = transform; 00959 } 00960 00961 PointCloud& cloud = info->transformed_points_; 00962 cloud.points.clear(); 00963 00964 size_t size = info->message_->width * info->message_->height; 00965 info->num_points_ = size; 00966 PointCloudPoint default_pt; 00967 default_pt.color = Ogre::ColourValue(1, 1, 1); 00968 default_pt.position = Ogre::Vector3::ZERO; 00969 cloud.points.resize(size, default_pt); 00970 00971 { 00972 boost::recursive_mutex::scoped_lock lock(transformers_mutex_); 00973 updateTransformers(info->message_, fully_update_transformers); 00974 PointCloudTransformerPtr xyz_trans = getXYZTransformer(info->message_); 00975 PointCloudTransformerPtr color_trans = getColorTransformer(info->message_); 00976 00977 if (!xyz_trans) 00978 { 00979 std::stringstream ss; 00980 ss << "No position transformer available for cloud"; 00981 setStatus(status_levels::Error, "Message", ss.str()); 00982 return false; 00983 } 00984 00985 if (!color_trans) 00986 { 00987 std::stringstream ss; 00988 ss << "No color transformer available for cloud"; 00989 setStatus(status_levels::Error, "Message", ss.str()); 00990 return false; 00991 } 00992 00993 xyz_trans->transform(info->message_, PointCloudTransformer::Support_XYZ, transform, cloud); 00994 color_trans->transform(info->message_, PointCloudTransformer::Support_Color, transform, cloud); 00995 } 00996 00997 points.resize(size); 00998 for (size_t i = 0; i < size; ++i) 00999 { 01000 Ogre::Vector3 pos = cloud.points[i].position; 01001 Ogre::ColourValue color = cloud.points[i].color; 01002 if (validateFloats(pos)) 01003 { 01004 points[i].x = pos.x; 01005 points[i].y = pos.y; 01006 points[i].z = pos.z; 01007 } 01008 else 01009 { 01010 points[i].x = 999999.0f; 01011 points[i].y = 999999.0f; 01012 points[i].z = 999999.0f; 01013 } 01014 points[i].setColor(color.r, color.g, color.b); 01015 } 01016 01017 return true; 01018 } 01019 01020 bool convertPointCloudToPointCloud2(const sensor_msgs::PointCloud& input, sensor_msgs::PointCloud2& output) 01021 { 01022 output.header = input.header; 01023 output.width = input.points.size (); 01024 output.height = 1; 01025 output.fields.resize (3 + input.channels.size ()); 01026 // Convert x/y/z to fields 01027 output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z"; 01028 int offset = 0; 01029 // All offsets are *4, as all field data types are float32 01030 for (size_t d = 0; d < output.fields.size (); ++d, offset += 4) 01031 { 01032 output.fields[d].offset = offset; 01033 output.fields[d].datatype = sensor_msgs::PointField::FLOAT32; 01034 } 01035 output.point_step = offset; 01036 output.row_step = output.point_step * output.width; 01037 // Convert the remaining of the channels to fields 01038 for (size_t d = 0; d < input.channels.size (); ++d) 01039 output.fields[3 + d].name = input.channels[d].name; 01040 output.data.resize (input.points.size () * output.point_step); 01041 output.is_bigendian = false; // @todo ? 01042 output.is_dense = false; 01043 01044 // Copy the data points 01045 for (size_t cp = 0; cp < input.points.size (); ++cp) 01046 { 01047 memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float)); 01048 memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float)); 01049 memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float)); 01050 for (size_t d = 0; d < input.channels.size (); ++d) 01051 { 01052 if (input.channels[d].values.size() == input.points.size()) 01053 { 01054 memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float)); 01055 } 01056 } 01057 } 01058 return (true); 01059 } 01060 01061 void PointCloudBase::addMessage(const sensor_msgs::PointCloudConstPtr& cloud) 01062 { 01063 sensor_msgs::PointCloud2Ptr out(new sensor_msgs::PointCloud2); 01064 convertPointCloudToPointCloud2(*cloud, *out); 01065 addMessage(out); 01066 } 01067 01068 void PointCloudBase::addMessage(const sensor_msgs::PointCloud2ConstPtr& cloud) 01069 { 01070 ++messages_received_; 01071 01072 if (cloud->width * cloud->height == 0) 01073 { 01074 return; 01075 } 01076 01077 processMessage(cloud); 01078 } 01079 01080 void PointCloudBase::fixedFrameChanged() 01081 { 01082 reset(); 01083 } 01084 01085 void PointCloudBase::onTransformerOptions(V_string& ops, uint32_t mask) 01086 { 01087 boost::mutex::scoped_lock clock(clouds_mutex_); 01088 01089 if (clouds_.empty()) 01090 { 01091 return; 01092 } 01093 01094 boost::recursive_mutex::scoped_lock tlock(transformers_mutex_); 01095 01096 const sensor_msgs::PointCloud2ConstPtr& msg = clouds_.front()->message_; 01097 01098 M_TransformerInfo::iterator it = transformers_.begin(); 01099 M_TransformerInfo::iterator end = transformers_.end(); 01100 for (; it != end; ++it) 01101 { 01102 const PointCloudTransformerPtr& trans = it->second.transformer; 01103 if ((trans->supports(msg) & mask) == mask) 01104 { 01105 ops.push_back(it->first); 01106 } 01107 } 01108 } 01109 01110 void PointCloudBase::createProperties() 01111 { 01112 selectable_property_ = property_manager_->createProperty<BoolProperty>( "Selectable", property_prefix_, 01113 boost::bind( &PointCloudBase::getSelectable, this ), 01114 boost::bind( &PointCloudBase::setSelectable, this, _1 ), 01115 parent_category_, this ); 01116 setPropertyHelpText( selectable_property_, "Whether or not the points in this point cloud are selectable." ); 01117 01118 style_property_ = property_manager_->createProperty<EnumProperty>( "Style", property_prefix_, 01119 boost::bind( &PointCloudBase::getStyle, this ), 01120 boost::bind( &PointCloudBase::setStyle, this, _1 ), 01121 parent_category_, this ); 01122 setPropertyHelpText( style_property_, "Rendering mode to use, in order of computational complexity." ); 01123 EnumPropertyPtr enum_prop = style_property_.lock(); 01124 enum_prop->addOption( "Points", Points ); 01125 enum_prop->addOption( "Billboards", Billboards ); 01126 enum_prop->addOption( "Billboard Spheres", BillboardSpheres ); 01127 enum_prop->addOption( "Boxes", Boxes ); 01128 01129 billboard_size_property_ = property_manager_->createProperty<FloatProperty>( "Billboard Size", property_prefix_, 01130 boost::bind( &PointCloudBase::getBillboardSize, this ), 01131 boost::bind( &PointCloudBase::setBillboardSize, this, _1 ), 01132 parent_category_, this ); 01133 setPropertyHelpText( billboard_size_property_, "Length, in meters, of the side of each billboard (or face if using the Boxes style)." ); 01134 FloatPropertyPtr float_prop = billboard_size_property_.lock(); 01135 float_prop->setMin( 0.0001 ); 01136 01137 alpha_property_ = property_manager_->createProperty<FloatProperty>( "Alpha", property_prefix_, 01138 boost::bind( &PointCloudBase::getAlpha, this ), 01139 boost::bind( &PointCloudBase::setAlpha, this, _1 ), 01140 parent_category_, this ); 01141 setPropertyHelpText( alpha_property_, 01142 "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct." ); 01143 decay_time_property_ = property_manager_->createProperty<FloatProperty>( "Decay Time", property_prefix_, 01144 boost::bind( &PointCloudBase::getDecayTime, this ), 01145 boost::bind( &PointCloudBase::setDecayTime, this, _1 ), 01146 parent_category_, this ); 01147 setPropertyHelpText( decay_time_property_, "Duration, in seconds, to keep the incoming points. 0 means only show the latest points." ); 01148 01149 xyz_transformer_property_ = 01150 property_manager_->createProperty<EditEnumProperty>( "Position Transformer", property_prefix_, 01151 boost::bind( &PointCloudBase::getXYZTransformer, this ), 01152 boost::bind( &PointCloudBase::setXYZTransformer, this, _1 ), 01153 parent_category_, this ); 01154 setPropertyHelpText( xyz_transformer_property_, "Set the transformer to use to set the position of the points." ); 01155 EditEnumPropertyPtr edit_enum_prop = xyz_transformer_property_.lock(); 01156 edit_enum_prop->setOptionCallback( boost::bind( &PointCloudBase::onTransformerOptions, this, _1, PointCloudTransformer::Support_XYZ )); 01157 01158 color_transformer_property_ = 01159 property_manager_->createProperty<EditEnumProperty>( "Color Transformer", property_prefix_, 01160 boost::bind( &PointCloudBase::getColorTransformer, this ), 01161 boost::bind( &PointCloudBase::setColorTransformer, this, _1 ), 01162 parent_category_, this ); 01163 setPropertyHelpText( color_transformer_property_, "Set the transformer to use to set the color of the points." ); 01164 edit_enum_prop = color_transformer_property_.lock(); 01165 edit_enum_prop->setOptionCallback( boost::bind( &PointCloudBase::onTransformerOptions, this, _1, PointCloudTransformer::Support_Color )); 01166 01167 // Create properties for transformers 01168 { 01169 boost::recursive_mutex::scoped_lock lock( transformers_mutex_ ); 01170 M_TransformerInfo::iterator it = transformers_.begin(); 01171 M_TransformerInfo::iterator end = transformers_.end(); 01172 for( ; it != end; ++it ) 01173 { 01174 const std::string& name = it->first; 01175 TransformerInfo& info = it->second; 01176 info.transformer->createProperties( property_manager_, parent_category_, 01177 property_prefix_ + "." + name, 01178 PointCloudTransformer::Support_XYZ, info.xyz_props ); 01179 info.transformer->createProperties( property_manager_, parent_category_, 01180 property_prefix_ + "." + name, 01181 PointCloudTransformer::Support_Color, info.color_props ); 01182 01183 if( name != getXYZTransformer() ) 01184 { 01185 std::for_each( info.xyz_props.begin(), info.xyz_props.end(), hideProperty<PropertyBase> ); 01186 } 01187 01188 if( name != getColorTransformer() ) 01189 { 01190 std::for_each( info.color_props.begin(), info.color_props.end(), hideProperty<PropertyBase> ); 01191 } 01192 } 01193 } 01194 } 01195 01196 void PointCloudBase::reset() 01197 { 01198 Display::reset(); 01199 01200 clouds_.clear(); 01201 cloud_->clear(); 01202 messages_received_ = 0; 01203 total_point_count_ = 0; 01204 } 01205 01206 } // namespace rviz