28 #include <QApplication> 29 #include <QMessageBox> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 59 #include <rtabmap_ros/GetMap.h> 60 #include <std_msgs/Int32MultiArray.h> 69 pose_(
rtabmap::Transform::getIdentity()),
101 "Rendering mode to use, in order of computational complexity.",
110 "Point size in meters.",
115 "Point size in pixels.",
120 "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
126 "Set the transformer to use to set the position of the points.",
132 "Set the transformer to use to set the color of the points.",
138 "Create the cloud from laser scans instead of the RGB-D/Stereo images.",
143 "Decimation of the input RGB and depth images before creating the cloud.",
149 "Maximum depth of the generated clouds.",
155 "Minimum depth of the generated clouds.",
161 "Voxel size of the generated clouds.",
167 "Filter the floor up to maximum height set here " 168 "(only appropriate for 2D mapping).",
174 "Filter the ceiling at the specified height set here " 175 "(only appropriate for 2D mapping).",
181 "(Disabled=0) Only keep one node in the specified radius.",
187 "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
195 "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
199 "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
222 std::vector<std::string>::iterator ci;
224 for( ci = classes.begin(); ci != classes.end(); ci++ )
226 const std::string& lookup_name = *ci;
231 ROS_ERROR(
"Transformer type [%s] is already loaded.", name.c_str() );
241 info.readable_name = name;
242 info.lookup_name = lookup_name;
277 std::map<int, rtabmap::Transform> poses;
278 for(
unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
285 std::set<int> nodeDataReceived;
286 for(
unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
288 int id = map.nodes[i].id;
298 cv::Mat image, depth;
303 sensor_msgs::PointCloud2::Ptr cloudMsg(
new sensor_msgs::PointCloud2);
306 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
307 pcl::IndicesPtr validIndices(
new std::vector<int>);
340 else if(!fromDepth && !scan.isEmpty())
348 pcl::PointCloud<pcl::PointXYZI>::Ptr cloud;
367 if(!cloudMsg->data.empty())
369 cloudMsg->header = map.header;
371 info->message_ = cloudMsg;
383 nodeDataReceived.insert(
id);
404 for(
int i = 0; i < props.size(); i++ )
406 props[ i ]->setHidden( hide );
419 typedef std::set<std::pair<uint8_t, std::string> >
S_string;
420 S_string valid_xyz, valid_color;
421 bool cur_xyz_valid =
false;
422 bool cur_color_valid =
false;
423 bool has_rgb_transformer =
false;
424 bool has_intensity_transformer =
false;
425 M_TransformerInfo::iterator trans_it =
transformers_.begin();
427 for(;trans_it != trans_end; ++trans_it)
429 const std::string&
name = trans_it->first;
434 valid_xyz.insert(std::make_pair(trans->score(cloud), name));
435 if (name == xyz_name)
437 cur_xyz_valid =
true;
444 valid_color.insert(std::make_pair(trans->score(cloud), name));
445 if (name == color_name)
447 cur_color_valid =
true;
451 has_rgb_transformer =
true;
453 else if (name ==
"Intensity")
455 has_intensity_transformer =
true;
463 if( !valid_xyz.empty() )
469 if( !cur_color_valid )
471 if( !valid_color.empty() )
473 if (has_rgb_transformer)
477 else if (has_intensity_transformer)
512 it->second->cloud_->setRenderMode( mode );
531 it->second->cloud_->setDimensions( size, size, size );
551 getMapSrv.request.global =
false;
552 getMapSrv.request.optimized =
true;
553 getMapSrv.request.graphOnly = graphOnly;
556 QMessageBox * messageBox =
new QMessageBox(
558 tr(
"Calling \"%1\" service...").arg(srvName.c_str()),
559 tr(
"Downloading the map... please wait (rviz could become gray!)"),
560 QMessageBox::NoButton);
561 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
563 QApplication::processEvents();
565 QApplication::processEvents();
568 ROS_ERROR(
"MapCloudDisplay: Cannot call \"%s\" service. " 569 "Tip: if rtabmap node is not in \"%s\" namespace, you can " 570 "change the \"Download namespace\" option.",
573 messageBox->setText(tr(
"MapCloudDisplay: Cannot call \"%1\" service. " 574 "Tip: if rtabmap node is not in \"%2\" namespace, you can " 575 "change the \"Download namespace\" option.").
576 arg(srvName.c_str()).arg(rtabmapNs.c_str()));
580 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
581 QApplication::processEvents();
583 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
585 QTimer::singleShot(1000, messageBox, SLOT(close()));
589 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)...")
590 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
591 QApplication::processEvents();
594 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
595 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
597 QTimer::singleShot(1000, messageBox, SLOT(close()));
655 int lastCloudAdded = -1;
676 for (; it != end; ++it)
681 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
682 cloud_info->cloud_->setRenderMode( mode );
684 cloud_info->cloud_->setDimensions( size, size, size );
685 cloud_info->cloud_->setAutoSize(
false);
689 cloud_info->scene_node_ =
scene_node_->createChildSceneNode();
691 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
692 cloud_info->scene_node_->setVisible(
false);
696 lastCloudAdded = it->first;
706 if( lock.owns_lock() )
712 for (; it != end; ++it)
714 const std::string&
name = it->first;
728 int totalNodesShown = 0;
734 std::vector<int> missingNodes;
737 std::map<int, CloudInfoPtr>::iterator cloudInfoIt =
cloud_infos_.find(it->first);
740 totalPoints += cloudInfoIt->second->transformed_points_.size();
741 cloudInfoIt->second->pose_ = it->second;
742 Ogre::Vector3 framePosition;
743 Ogre::Quaternion frameOrientation;
748 Ogre::Matrix4 frameTransform;
749 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
751 Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
752 p[4], p[5], p[6], p[7],
753 p[8], p[9], p[10], p[11],
755 frameTransform = frameTransform * pose;
756 Ogre::Vector3 posePosition = frameTransform.getTrans();
757 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
758 poseOrientation.normalise();
760 cloudInfoIt->second->scene_node_->setPosition(posePosition);
761 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
762 cloudInfoIt->second->scene_node_->setVisible(
true);
767 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\")",
769 cloudInfoIt->second->message_->header.frame_id.c_str(),
771 cloudInfoIt->second->message_->header.frame_id.c_str());
776 missingNodes.push_back(it->first);
792 iter->second->scene_node_->setVisible(
false);
802 if(!missingNodes.empty())
804 std_msgs::Int32MultiArray msg;
805 msg.data = missingNodes;
880 const sensor_msgs::PointCloud2ConstPtr& msg =
cloud_infos_.begin()->second->message_;
884 for (; it != end; ++it)
887 if ((trans->supports(msg) &
mask) == mask)
889 prop->
addOption( QString::fromStdString( it->first ));
935 cloud_info->cloud_->clear();
936 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
943 cloud_points.clear();
945 size_t size = cloud_info->message_->width * cloud_info->message_->height;
947 default_pt.
color = Ogre::ColourValue(1, 1, 1);
948 default_pt.
position = Ogre::Vector3::ZERO;
949 cloud_points.resize(size, default_pt);
953 if( update_transformers )
962 std::stringstream ss;
963 ss <<
"No position transformer available for cloud";
970 std::stringstream ss;
971 ss <<
"No color transformer available for cloud";
980 for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
984 cloud_point->position.x = 999999.0f;
985 cloud_point->position.y = 999999.0f;
986 cloud_point->position.z = 999999.0f;
ros::ServiceClient getMapSrv
void updateTransformers(const sensor_msgs::PointCloud2ConstPtr &cloud)
GLM_FUNC_DECL genIType mask(genIType const &count)
bool new_color_transformer_
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
void setStringStd(const std::string &str)
rviz::StringProperty * download_namespace
void updateCloudParameters()
std::string uFormat(const char *fmt,...)
std::set< std::string > S_string
rviz::EnumProperty * style_property_
std::map< int, Transform > RTABMAP_EXP radiusPosesFiltering(const std::map< int, Transform > &poses, float radius, float angle, bool keepLatest=true)
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &msg)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pluginlib::ClassLoader< rviz::PointCloudTransformer > * transformer_class_loader_
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
Displays point clouds from rtabmap::MapData.
const LaserScan & laserScanCompressed() const
rviz::FloatProperty * cloud_voxel_size_
DisplayContext * context_
rviz::FloatProperty * cloud_max_depth_
bool call(const std::string &service_name, MReq &req, MRes &res)
void emitTimeSignal(ros::Time time)
const cv::Mat & depthOrRightRaw() const
ros::NodeHandle update_nh_
ros::AsyncSpinner spinner_
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
const std::vector< StereoCameraModel > & stereoCameraModels() const
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg, bool ignoreRotationIfNotSet=false)
virtual void clearOptions()
rviz::IntProperty * cloud_decimation_
rviz::EnumProperty * xyz_transformer_property_
rviz::PointCloudTransformerPtr getColorTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
T * createUnmanagedInstance(const std::string &lookup_name)
rviz::FloatProperty * cloud_filter_ceiling_height_
rviz::FloatProperty * alpha_property_
std::map< int, CloudInfoPtr > cloud_infos_
rviz::FloatProperty * point_pixel_size_property_
M_TransformerInfo transformers_
rviz::FloatProperty * node_filtering_radius_
rviz::BoolProperty * cloud_from_scan_
std::map< int, rtabmap::Transform > current_map_
rviz::BoolProperty * download_map_
void downloadNamespaceChanged()
boost::shared_ptr< PointCloudTransformer > PointCloudTransformerPtr
rviz::PointCloudTransformerPtr getXYZTransformer(const sensor_msgs::PointCloud2ConstPtr &cloud)
Ogre::SceneNode * scene_node_
std::string getStdString()
bool new_xyz_transformer_
rviz::FloatProperty * node_filtering_angle_
rviz::FloatProperty * point_world_size_property_
const std::vector< CameraModel > & cameraModels() const
bool transformCloud(const CloudInfoPtr &cloud, bool fully_update_transformers)
Transforms the cloud into the correct frame, and sets up our renderable cloud.
LaserScan RTABMAP_EXP commonFiltering(const LaserScan &scan, int downsamplingStep, float rangeMin=0.0f, float rangeMax=0.0f, float voxelSize=0.0f, int normalK=0, float normalRadius=0.0f, float groundNormalsUp=0.0f)
void publish(const boost::shared_ptr< M > &message) const
virtual void addOption(const QString &option, int value=0)
boost::recursive_mutex transformers_mutex_
const cv::Mat & imageRaw() const
void fillTransformerOptions(rviz::EnumProperty *prop, uint32_t mask)
void setCallbackQueue(CallbackQueueInterface *queue)
rviz::FloatProperty * cloud_min_depth_
std::vector< std::string > getDeclaredClasses()
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
std::map< int, CloudInfoPtr > new_cloud_infos_
std::vector< PointCloud::Point > V_PointCloudPoint
virtual FrameManager * getFrameManager() const=0
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
void addOptionStd(const std::string &option, int value=0)
ros::CallbackQueue cbqueue_
const cv::Mat & depthOrRightCompressed() const
virtual std::string getName(const std::string &lookup_name)
void processMapData(const rtabmap_ros::MapData &map)
virtual void update(float wall_dt, float ros_dt)
void uSleep(unsigned int ms)
virtual int getInt() const
void updateColorTransformer()
virtual Ogre::SceneManager * getSceneManager() const=0
virtual void queueRender()=0
rviz::FloatProperty * cloud_filter_floor_height_
void updateBillboardSize()
virtual ~MapCloudDisplay()
Ogre::SceneManager * manager_
SensorData & sensorData()
void updateXyzTransformer()
boost::mutex current_map_mutex_
virtual float getFloat() const
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setPropertiesHidden(const QList< Property *> &props, bool hide)
bool frameHasProblems(const std::string &frame, ros::Time time, std::string &error)
const Transform & getPose() const
void onInitialize() override
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
rviz::EnumProperty * color_transformer_property_
boost::mutex new_clouds_mutex_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
bool current_map_updated_
std::set< int > nodeDataReceived_
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
ros::Publisher republishNodeDataPub_
virtual bool getBool() const
virtual int getOptionInt()
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
rviz::BoolProperty * download_graph_
Ogre::SceneNode * scene_node_
void setColorTransformerOptions(EnumProperty *prop)
const cv::Mat & imageCompressed() const
virtual void processMessage(const rtabmap_ros::MapDataConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
void setXyzTransformerOptions(EnumProperty *prop)