30 #include <QApplication>
31 #include <QMessageBox>
34 #include <OgreSceneNode.h>
35 #include <OgreSceneManager.h>
60 #include <rtabmap_msgs/GetMap.h>
61 #include <std_msgs/Int32MultiArray.h>
70 pose_(
rtabmap::Transform::getIdentity()),
102 "Rendering mode to use, in order of computational complexity.",
111 "Point size in meters.",
116 "Point size in pixels.",
121 "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
127 "Set the transformer to use to set the position of the points.",
133 "Set the transformer to use to set the color of the points.",
139 "Create the cloud from laser scans instead of the RGB-D/Stereo images.",
144 "Decimation of the input RGB and depth images before creating the cloud.",
150 "Maximum depth of the generated clouds.",
156 "Minimum depth of the generated clouds.",
162 "Voxel size of the generated clouds.",
168 "Filter the floor up to maximum height set here "
169 "(only appropriate for 2D mapping).",
175 "Filter the ceiling at the specified height set here "
176 "(only appropriate for 2D mapping).",
182 "(Disabled=0) Only keep one node in the specified radius.",
188 "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
196 "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
200 "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
223 std::vector<std::string>::iterator ci;
225 for( ci = classes.begin(); ci != classes.end(); ci++ )
227 const std::string& lookup_name = *ci;
232 ROS_ERROR(
"Transformer type [%s] is already loaded.",
name.c_str() );
243 info.lookup_name = lookup_name;
278 std::map<int, rtabmap::Transform> poses;
279 for(
unsigned int i=0;
i<map.graph.posesId.size() &&
i<map.graph.poses.size(); ++
i)
286 std::set<int> nodeDataReceived;
287 for(
unsigned int i=0;
i<map.nodes.size() &&
i<map.nodes.size(); ++
i)
289 int id = map.nodes[
i].id;
294 !
s.sensorData().imageCompressed().empty() &&
295 !
s.sensorData().depthOrRightCompressed().empty() &&
296 (
s.sensorData().cameraModels().size() ||
s.sensorData().stereoCameraModels().size())) ||
297 (!fromDepth && !
s.sensorData().laserScanCompressed().isEmpty()))
299 cv::Mat image, depth;
302 s.sensorData().uncompressData(fromDepth?&image:0, fromDepth?&depth:0, !fromDepth?&scan:0);
304 sensor_msgs::PointCloud2::Ptr cloudMsg(
new sensor_msgs::PointCloud2);
305 if(fromDepth && !
s.sensorData().imageRaw().empty() && !
s.sensorData().depthOrRightRaw().empty())
307 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
308 pcl::IndicesPtr validIndices(
new std::vector<int>);
341 else if(!fromDepth && !scan.isEmpty())
349 pcl::PointCloud<pcl::PointXYZI>::Ptr cloud;
368 if(!cloudMsg->data.empty())
370 cloudMsg->header = map.header;
372 info->message_ = cloudMsg;
384 nodeDataReceived.insert(
id);
405 for(
int i = 0;
i < props.size();
i++ )
407 props[
i ]->setHidden(
hide );
420 typedef std::set<std::pair<uint8_t, std::string> >
S_string;
422 bool cur_xyz_valid =
false;
423 bool cur_color_valid =
false;
424 bool has_rgb_transformer =
false;
425 bool has_intensity_transformer =
false;
426 M_TransformerInfo::iterator trans_it =
transformers_.begin();
428 for(;trans_it != trans_end; ++trans_it)
430 const std::string&
name = trans_it->first;
435 valid_xyz.insert(std::make_pair(
trans->score(cloud),
name));
436 if (
name == xyz_name)
438 cur_xyz_valid =
true;
445 valid_color.insert(std::make_pair(
trans->score(cloud),
name));
446 if (
name == color_name)
448 cur_color_valid =
true;
452 has_rgb_transformer =
true;
454 else if (
name ==
"Intensity")
456 has_intensity_transformer =
true;
464 if( !valid_xyz.empty() )
470 if( !cur_color_valid )
472 if( !valid_color.empty() )
474 if (has_rgb_transformer)
478 else if (has_intensity_transformer)
513 it->second->cloud_->setRenderMode(
mode );
551 rtabmap_msgs::GetMap getMapSrv;
552 getMapSrv.request.global =
false;
553 getMapSrv.request.optimized =
true;
554 getMapSrv.request.graphOnly = graphOnly;
557 QMessageBox * messageBox =
new QMessageBox(
559 tr(
"Calling \"%1\" service...").
arg(srvName.c_str()),
560 tr(
"Downloading the map... please wait (rviz could become gray!)"),
561 QMessageBox::NoButton);
562 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
564 QApplication::processEvents();
566 QApplication::processEvents();
569 ROS_ERROR(
"MapCloudDisplay: Cannot call \"%s\" service. "
570 "Tip: if rtabmap node is not in \"%s\" namespace, you can "
571 "change the \"Download namespace\" option.",
574 messageBox->setText(tr(
"MapCloudDisplay: Cannot call \"%1\" service. "
575 "Tip: if rtabmap node is not in \"%2\" namespace, you can "
576 "change the \"Download namespace\" option.").
577 arg(srvName.c_str()).
arg(rtabmapNs.c_str()));
581 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)...").
arg(getMapSrv.response.data.graph.poses.size()));
582 QApplication::processEvents();
584 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)... done!").
arg(getMapSrv.response.data.graph.poses.size()));
586 QTimer::singleShot(1000, messageBox, SLOT(close()));
590 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)...")
591 .
arg(getMapSrv.response.data.graph.poses.size()).
arg(getMapSrv.response.data.nodes.size()));
592 QApplication::processEvents();
595 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
596 .
arg(getMapSrv.response.data.graph.poses.size()).
arg(getMapSrv.response.data.nodes.size()));
598 QTimer::singleShot(1000, messageBox, SLOT(close()));
656 int lastCloudAdded = -1;
677 for (; it !=
end; ++it)
682 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
683 cloud_info->cloud_->setRenderMode(
mode );
686 cloud_info->cloud_->setAutoSize(
false);
690 cloud_info->scene_node_ =
scene_node_->createChildSceneNode();
692 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
693 cloud_info->scene_node_->setVisible(
false);
697 lastCloudAdded = it->first;
707 if( lock.owns_lock() )
713 for (; it !=
end; ++it)
715 const std::string&
name = it->first;
729 int totalNodesShown = 0;
735 std::vector<int> missingNodes;
738 std::map<int, CloudInfoPtr>::iterator cloudInfoIt =
cloud_infos_.find(it->first);
741 totalPoints += cloudInfoIt->second->transformed_points_.size();
742 cloudInfoIt->second->pose_ = it->second;
743 Ogre::Vector3 framePosition;
744 Ogre::Quaternion frameOrientation;
749 Ogre::Matrix4 frameTransform;
750 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
752 Ogre::Matrix4 pose(
p[0],
p[1],
p[2],
p[3],
753 p[4],
p[5],
p[6],
p[7],
754 p[8],
p[9],
p[10],
p[11],
756 frameTransform = frameTransform * pose;
757 Ogre::Vector3 posePosition = frameTransform.getTrans();
758 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
759 poseOrientation.normalise();
761 cloudInfoIt->second->scene_node_->setPosition(posePosition);
762 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
763 cloudInfoIt->second->scene_node_->setVisible(
true);
768 ROS_ERROR(
"MapCloudDisplay: Could not update pose of node %d (cannot transform pose in target frame id \"%s\" (reason=%s), set fixed frame in global options to \"%s\")",
770 cloudInfoIt->second->message_->header.frame_id.c_str(),
772 cloudInfoIt->second->message_->header.frame_id.c_str());
777 missingNodes.push_back(it->first);
793 iter->second->scene_node_->setVisible(
false);
803 if(!missingNodes.empty())
805 std_msgs::Int32MultiArray
msg;
806 msg.data = missingNodes;
881 const sensor_msgs::PointCloud2ConstPtr&
msg =
cloud_infos_.begin()->second->message_;
885 for (; it !=
end; ++it)
890 prop->
addOption( QString::fromStdString( it->first ));
936 cloud_info->cloud_->clear();
937 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
944 cloud_points.clear();
946 size_t size = cloud_info->message_->width * cloud_info->message_->height;
948 default_pt.
color = Ogre::ColourValue(1, 1, 1);
949 default_pt.
position = Ogre::Vector3::ZERO;
950 cloud_points.resize(
size, default_pt);
954 if( update_transformers )
963 std::stringstream ss;
964 ss <<
"No position transformer available for cloud";
971 std::stringstream ss;
972 ss <<
"No color transformer available for cloud";
981 for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
985 cloud_point->position.x = 999999.0f;
986 cloud_point->position.y = 999999.0f;
987 cloud_point->position.z = 999999.0f;