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