28 #include <QApplication> 29 #include <QMessageBox> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 59 #include <rtabmap_ros/GetMap.h> 68 pose_(
rtabmap::Transform::getIdentity()),
99 "Rendering mode to use, in order of computational complexity.",
108 "Point size in meters.",
113 "Point size in pixels.",
118 "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
124 "Set the transformer to use to set the position of the points.",
130 "Set the transformer to use to set the color of the points.",
136 "Create the cloud from laser scans instead of the RGB-D/Stereo images.",
140 "Decimation of the input RGB and depth images before creating the cloud.",
146 "Maximum depth of the generated clouds.",
152 "Minimum depth of the generated clouds.",
158 "Voxel size of the generated clouds.",
164 "Filter the floor up to maximum height set here " 165 "(only appropriate for 2D mapping).",
171 "Filter the ceiling at the specified height set here " 172 "(only appropriate for 2D mapping).",
178 "(Disabled=0) Only keep one node in the specified radius.",
184 "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
190 "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
194 "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
215 std::vector<std::string>::iterator ci;
217 for( ci = classes.begin(); ci != classes.end(); ci++ )
219 const std::string& lookup_name = *ci;
224 ROS_ERROR(
"Transformer type [%s] is already loaded.", name.c_str() );
234 info.readable_name = name;
235 info.lookup_name = lookup_name;
270 std::map<int, rtabmap::Transform> poses;
271 for(
unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
278 for(
unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
280 int id = map.nodes[i].id;
290 cv::Mat image, depth;
295 sensor_msgs::PointCloud2::Ptr cloudMsg(
new sensor_msgs::PointCloud2);
298 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
299 pcl::IndicesPtr validIndices(
new std::vector<int>);
332 else if(!fromDepth && !scan.isEmpty())
340 pcl::PointCloud<pcl::PointXYZI>::Ptr cloud;
359 if(!cloudMsg->data.empty())
361 cloudMsg->header = map.header;
363 info->message_ = cloudMsg;
393 for(
int i = 0; i < props.size(); i++ )
395 props[ i ]->setHidden( hide );
408 typedef std::set<std::pair<uint8_t, std::string> >
S_string;
409 S_string valid_xyz, valid_color;
410 bool cur_xyz_valid =
false;
411 bool cur_color_valid =
false;
412 bool has_rgb_transformer =
false;
413 bool has_intensity_transformer =
false;
414 M_TransformerInfo::iterator trans_it =
transformers_.begin();
416 for(;trans_it != trans_end; ++trans_it)
418 const std::string& name = trans_it->first;
423 valid_xyz.insert(std::make_pair(trans->score(cloud), name));
424 if (name == xyz_name)
426 cur_xyz_valid =
true;
433 valid_color.insert(std::make_pair(trans->score(cloud), name));
434 if (name == color_name)
436 cur_color_valid =
true;
440 has_rgb_transformer =
true;
442 else if (name ==
"Intensity")
444 has_intensity_transformer =
true;
452 if( !valid_xyz.empty() )
458 if( !cur_color_valid )
460 if( !valid_color.empty() )
462 if (has_rgb_transformer)
466 else if (has_intensity_transformer)
501 it->second->cloud_->setRenderMode( mode );
520 it->second->cloud_->setDimensions( size, size, size );
535 getMapSrv.request.global =
true;
536 getMapSrv.request.optimized =
true;
537 getMapSrv.request.graphOnly =
false;
539 QMessageBox * messageBox =
new QMessageBox(
541 tr(
"Calling \"%1\" service...").arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()),
542 tr(
"Downloading the map... please wait (rviz could become gray!)"),
543 QMessageBox::NoButton);
544 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
546 QApplication::processEvents();
548 QApplication::processEvents();
551 ROS_ERROR(
"MapCloudDisplay: Can't call \"%s\" service. " 552 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 553 "to \"get_map_data\" in the launch " 554 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
556 messageBox->setText(tr(
"MapCloudDisplay: Can't call \"%1\" service. " 557 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 558 "to \"get_map_data\" in the launch " 559 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
560 arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()));
564 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)...")
565 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
566 QApplication::processEvents();
569 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
570 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
572 QTimer::singleShot(1000, messageBox, SLOT(close()));
593 getMapSrv.request.global =
true;
594 getMapSrv.request.optimized =
true;
595 getMapSrv.request.graphOnly =
true;
597 QMessageBox * messageBox =
new QMessageBox(
599 tr(
"Calling \"%1\" service...").arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()),
600 tr(
"Downloading the graph... please wait (rviz could become gray!)"),
601 QMessageBox::NoButton);
602 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
604 QApplication::processEvents();
606 QApplication::processEvents();
609 ROS_ERROR(
"MapCloudDisplay: Can't call \"%s\" service. " 610 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 611 "to \"get_map_data\" in the launch " 612 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
614 messageBox->setText(tr(
"MapCloudDisplay: Can't call \"%1\" service. " 615 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 616 "to \"get_map_data\" in the launch " 617 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
618 arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()));
622 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
623 QApplication::processEvents();
625 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
627 QTimer::singleShot(1000, messageBox, SLOT(close()));
652 int lastCloudAdded = -1;
673 for (; it != end; ++it)
678 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
679 cloud_info->cloud_->setRenderMode( mode );
681 cloud_info->cloud_->setDimensions( size, size, size );
682 cloud_info->cloud_->setAutoSize(
false);
686 cloud_info->scene_node_ =
scene_node_->createChildSceneNode();
688 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
689 cloud_info->scene_node_->setVisible(
false);
693 lastCloudAdded = it->first;
703 if( lock.owns_lock() )
709 for (; it != end; ++it)
711 const std::string& name = it->first;
725 int totalNodesShown = 0;
733 std::map<int, CloudInfoPtr>::iterator cloudInfoIt =
cloud_infos_.find(it->first);
736 totalPoints += cloudInfoIt->second->transformed_points_.size();
737 cloudInfoIt->second->pose_ = it->second;
738 Ogre::Vector3 framePosition;
739 Ogre::Quaternion frameOrientation;
743 Ogre::Matrix4 frameTransform;
744 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
746 Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
747 p[4], p[5], p[6], p[7],
748 p[8], p[9], p[10], p[11],
750 frameTransform = frameTransform * pose;
751 Ogre::Vector3 posePosition = frameTransform.getTrans();
752 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
753 poseOrientation.normalise();
755 cloudInfoIt->second->scene_node_->setPosition(posePosition);
756 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
757 cloudInfoIt->second->scene_node_->setVisible(
true);
762 ROS_ERROR(
"MapCloudDisplay: Could not update pose of node %d", it->first);
780 iter->second->scene_node_->setVisible(
false);
858 const sensor_msgs::PointCloud2ConstPtr& msg =
cloud_infos_.begin()->second->message_;
862 for (; it != end; ++it)
865 if ((trans->supports(msg) &
mask) == mask)
867 prop->
addOption( QString::fromStdString( it->first ));
913 cloud_info->cloud_->clear();
914 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
921 cloud_points.clear();
923 size_t size = cloud_info->message_->width * cloud_info->message_->height;
925 default_pt.
color = Ogre::ColourValue(1, 1, 1);
926 default_pt.
position = Ogre::Vector3::ZERO;
927 cloud_points.resize(size, default_pt);
931 if( update_transformers )
940 std::stringstream ss;
941 ss <<
"No position transformer available for cloud";
948 std::stringstream ss;
949 ss <<
"No color transformer available for cloud";
958 for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
962 cloud_point->position.x = 999999.0f;
963 cloud_point->position.y = 999999.0f;
964 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)
void updateCloudParameters()
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)
const LaserScan & laserScanCompressed() const
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
virtual void onInitialize()
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.
rviz::FloatProperty * cloud_voxel_size_
DisplayContext * context_
std::string resolveName(const std::string &name, bool remap=true) const
rviz::FloatProperty * cloud_max_depth_
bool call(const std::string &service_name, MReq &req, MRes &res)
void emitTimeSignal(ros::Time time)
virtual int getInt() const
ros::NodeHandle update_nh_
ros::AsyncSpinner spinner_
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
virtual float getFloat() 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_
const cv::Mat & imageRaw() const
std::map< int, rtabmap::Transform > current_map_
rviz::BoolProperty * download_map_
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_
virtual bool getBool() const
bool isValidForProjection() const
rviz::FloatProperty * point_world_size_property_
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)
const cv::Mat & depthOrRightCompressed() const
virtual void addOption(const QString &option, int value=0)
boost::recursive_mutex transformers_mutex_
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
const cv::Mat & depthOrRightRaw() const
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
void addOptionStd(const std::string &option, int value=0)
ros::CallbackQueue cbqueue_
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)
void updateColorTransformer()
virtual Ogre::SceneManager * getSceneManager() const =0
const std::vector< CameraModel > & cameraModels() const
const Transform & getPose() const
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_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
const StereoCameraModel & stereoCameraModel() const
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
rviz::EnumProperty * color_transformer_property_
boost::mutex new_clouds_mutex_
const cv::Mat & imageCompressed() const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
pcl::PointCloud< pcl::PointXYZI >::Ptr RTABMAP_EXP laserScanToPointCloudI(const LaserScan &laserScan, const Transform &transform=Transform(), float intensity=0.0f)
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)
virtual void processMessage(const rtabmap_ros::MapDataConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
void setPropertiesHidden(const QList< Property * > &props, bool hide)
void setXyzTransformerOptions(EnumProperty *prop)