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()),
98 "Rendering mode to use, in order of computational complexity.",
107 "Point size in meters.",
112 "Point size in pixels.",
117 "Amount of transparency to apply to the points. Note that this is experimental and does not always look correct.",
123 "Set the transformer to use to set the position of the points.",
129 "Set the transformer to use to set the color of the points.",
135 "Decimation of the input RGB and depth images before creating the cloud.",
141 "Maximum depth of the generated clouds.",
147 "Minimum depth of the generated clouds.",
153 "Voxel size of the generated clouds.",
159 "Filter the floor up to maximum height set here " 160 "(only appropriate for 2D mapping).",
166 "Filter the ceiling at the specified height set here " 167 "(only appropriate for 2D mapping).",
173 "(Disabled=0) Only keep one node in the specified radius.",
179 "(Disabled=0) Only keep one node in the specified angle in the filtering radius.",
185 "Download the optimized global map using rtabmap/GetMap service. This will force to re-create all clouds.",
189 "Download the optimized global graph (without cloud data) using rtabmap/GetMap service.",
210 std::vector<std::string>::iterator ci;
212 for( ci = classes.begin(); ci != classes.end(); ci++ )
214 const std::string& lookup_name = *ci;
219 ROS_ERROR(
"Transformer type [%s] is already loaded.", name.c_str() );
229 info.readable_name = name;
230 info.lookup_name = lookup_name;
265 std::map<int, rtabmap::Transform> poses;
266 for(
unsigned int i=0; i<map.graph.posesId.size() && i<map.graph.poses.size(); ++i)
272 for(
unsigned int i=0; i<map.nodes.size() && i<map.nodes.size(); ++i)
274 int id = map.nodes[i].id;
282 cv::Mat image, depth;
288 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
289 pcl::IndicesPtr validIndices(
new std::vector<int>);
315 sensor_msgs::PointCloud2::Ptr cloudMsg(
new sensor_msgs::PointCloud2);
317 cloudMsg->header = map.header;
320 info->message_ = cloudMsg;
351 for(
int i = 0; i < props.size(); i++ )
353 props[ i ]->setHidden( hide );
366 typedef std::set<std::pair<uint8_t, std::string> >
S_string;
367 S_string valid_xyz, valid_color;
368 bool cur_xyz_valid =
false;
369 bool cur_color_valid =
false;
370 bool has_rgb_transformer =
false;
371 M_TransformerInfo::iterator trans_it =
transformers_.begin();
373 for(;trans_it != trans_end; ++trans_it)
375 const std::string& name = trans_it->first;
380 valid_xyz.insert(std::make_pair(trans->score(cloud), name));
381 if (name == xyz_name)
383 cur_xyz_valid =
true;
390 valid_color.insert(std::make_pair(trans->score(cloud), name));
391 if (name == color_name)
393 cur_color_valid =
true;
397 has_rgb_transformer =
true;
405 if( !valid_xyz.empty() )
411 if( !cur_color_valid )
413 if( !valid_color.empty() )
415 if (has_rgb_transformer)
450 it->second->cloud_->setRenderMode( mode );
469 it->second->cloud_->setDimensions( size, size, size );
483 rtabmap_ros::GetMap getMapSrv;
484 getMapSrv.request.global =
true;
485 getMapSrv.request.optimized =
true;
486 getMapSrv.request.graphOnly =
false;
488 QMessageBox * messageBox =
new QMessageBox(
490 tr(
"Calling \"%1\" service...").arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()),
491 tr(
"Downloading the map... please wait (rviz could become gray!)"),
492 QMessageBox::NoButton);
493 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
495 QApplication::processEvents();
497 QApplication::processEvents();
500 ROS_ERROR(
"MapCloudDisplay: Can't call \"%s\" service. " 501 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 502 "to \"get_map_data\" in the launch " 503 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
505 messageBox->setText(tr(
"MapCloudDisplay: Can't call \"%1\" service. " 506 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 507 "to \"get_map_data\" in the launch " 508 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
509 arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()));
513 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)...")
514 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
515 QApplication::processEvents();
518 messageBox->setText(tr(
"Creating all clouds (%1 poses and %2 clouds downloaded)... done!")
519 .arg(getMapSrv.response.data.graph.poses.size()).arg(getMapSrv.response.data.nodes.size()));
521 QTimer::singleShot(1000, messageBox, SLOT(close()));
541 rtabmap_ros::GetMap getMapSrv;
542 getMapSrv.request.global =
true;
543 getMapSrv.request.optimized =
true;
544 getMapSrv.request.graphOnly =
true;
546 QMessageBox * messageBox =
new QMessageBox(
548 tr(
"Calling \"%1\" service...").arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()),
549 tr(
"Downloading the graph... please wait (rviz could become gray!)"),
550 QMessageBox::NoButton);
551 messageBox->setAttribute(Qt::WA_DeleteOnClose,
true);
553 QApplication::processEvents();
555 QApplication::processEvents();
558 ROS_ERROR(
"MapCloudDisplay: Can't call \"%s\" service. " 559 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 560 "to \"get_map_data\" in the launch " 561 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.",
563 messageBox->setText(tr(
"MapCloudDisplay: Can't call \"%1\" service. " 564 "Tip: if rtabmap node is not in rtabmap namespace, you can remap the service " 565 "to \"get_map_data\" in the launch " 566 "file like: <remap from=\"rtabmap/get_map_data\" to=\"get_map_data\"/>.").
567 arg(nh.
resolveName(
"rtabmap/get_map_data").c_str()));
571 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)...").arg(getMapSrv.response.data.graph.poses.size()));
572 QApplication::processEvents();
574 messageBox->setText(tr(
"Updating the map (%1 nodes downloaded)... done!").arg(getMapSrv.response.data.graph.poses.size()));
576 QTimer::singleShot(1000, messageBox, SLOT(close()));
620 for (; it != end; ++it)
625 cloud_info->cloud_->addPoints( &(cloud_info->transformed_points_.front()), cloud_info->transformed_points_.size() );
626 cloud_info->cloud_->setRenderMode( mode );
628 cloud_info->cloud_->setDimensions( size, size, size );
629 cloud_info->cloud_->setAutoSize(
false);
633 cloud_info->scene_node_ =
scene_node_->createChildSceneNode();
635 cloud_info->scene_node_->attachObject( cloud_info->cloud_.get() );
636 cloud_info->scene_node_->setVisible(
false);
649 if( lock.owns_lock() )
655 for (; it != end; ++it)
657 const std::string& name = it->first;
671 int totalNodesShown = 0;
679 std::map<int, CloudInfoPtr>::iterator cloudInfoIt =
cloud_infos_.find(it->first);
682 totalPoints += cloudInfoIt->second->transformed_points_.size();
683 cloudInfoIt->second->pose_ = it->second;
684 Ogre::Vector3 framePosition;
685 Ogre::Quaternion frameOrientation;
689 Ogre::Matrix4 frameTransform;
690 frameTransform.makeTransform( framePosition, Ogre::Vector3(1,1,1), frameOrientation);
692 Ogre::Matrix4 pose(p[0], p[1], p[2], p[3],
693 p[4], p[5], p[6], p[7],
694 p[8], p[9], p[10], p[11],
696 frameTransform = frameTransform * pose;
697 Ogre::Vector3 posePosition = frameTransform.getTrans();
698 Ogre::Quaternion poseOrientation = frameTransform.extractQuaternion();
699 poseOrientation.normalise();
701 cloudInfoIt->second->scene_node_->setPosition(posePosition);
702 cloudInfoIt->second->scene_node_->setOrientation(poseOrientation);
703 cloudInfoIt->second->scene_node_->setVisible(
true);
708 ROS_ERROR(
"MapCloudDisplay: Could not update pose of node %d", it->first);
718 iter->second->scene_node_->setVisible(
false);
785 const sensor_msgs::PointCloud2ConstPtr& msg =
cloud_infos_.begin()->second->message_;
789 for (; it != end; ++it)
792 if ((trans->supports(msg) &
mask) == mask)
794 prop->
addOption( QString::fromStdString( it->first ));
840 cloud_info->cloud_->clear();
841 cloud_info->cloud_->addPoints(&cloud_info->transformed_points_.front(), cloud_info->transformed_points_.size());
848 cloud_points.clear();
850 size_t size = cloud_info->message_->width * cloud_info->message_->height;
852 default_pt.
color = Ogre::ColourValue(1, 1, 1);
853 default_pt.
position = Ogre::Vector3::ZERO;
854 cloud_points.resize(size, default_pt);
858 if( update_transformers )
867 std::stringstream ss;
868 ss <<
"No position transformer available for cloud";
875 std::stringstream ss;
876 ss <<
"No color transformer available for cloud";
885 for (rviz::V_PointCloudPoint::iterator cloud_point = cloud_points.begin(); cloud_point != cloud_points.end(); ++cloud_point)
889 cloud_point->position.x = 999999.0f;
890 cloud_point->position.y = 999999.0f;
891 cloud_point->position.z = 999999.0f;
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)
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
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_
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.
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)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
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)
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)