@@ -1433,20 +1433,18 @@ void MainWindow::updateMapCloud(
14331433 {
14341434 // Find all graphs
14351435 std::map<int , pcl::PointCloud<pcl::PointXYZ>::Ptr > graphs;
1436- pcl::PointCloud<pcl::PointXYZ>::Ptr graphNodes (new pcl::PointCloud<pcl::PointXYZ>);
1437- graphNodes->resize (_currentPosesMap.size ());
1438- int oi = 0 ;
14391436 for (std::map<int , Transform>::iterator iter=_currentPosesMap.begin (); iter!=_currentPosesMap.end (); ++iter)
14401437 {
14411438 int mapId = uValue (_currentMapIds, iter->first , -1 );
1439+
1440+ // edges
14421441 std::map<int , pcl::PointCloud<pcl::PointXYZ>::Ptr >::iterator kter = graphs.find (mapId);
14431442 if (kter == graphs.end ())
14441443 {
14451444 kter = graphs.insert (std::make_pair (mapId, pcl::PointCloud<pcl::PointXYZ>::Ptr (new pcl::PointCloud<pcl::PointXYZ>))).first ;
14461445 }
14471446 pcl::PointXYZ pt (iter->second .x (), iter->second .y (), iter->second .z ());
14481447 kter->second ->push_back (pt);
1449- (*graphNodes)[oi++] = pcl::PointXYZ (pt);
14501448 }
14511449
14521450 // add graphs
@@ -1455,14 +1453,10 @@ void MainWindow::updateMapCloud(
14551453 QColor color = Qt::gray;
14561454 if (iter->first >= 0 )
14571455 {
1458- color = (Qt::GlobalColor)((iter->first +2 ) % 12 + 7 );
1456+ color = (Qt::GlobalColor)((iter->first +3 ) % 12 + 7 );
14591457 }
14601458 _ui->widget_cloudViewer ->addOrUpdateGraph (uFormat (" graph_%d" , iter->first ), iter->second , color);
14611459 }
1462-
1463- // add nodes
1464- _ui->widget_cloudViewer ->addOrUpdateCloud (" graph_nodes" , graphNodes, Transform::getIdentity (), Qt::green);
1465- _ui->widget_cloudViewer ->setCloudPointSize (" graph_nodes" , 5 );
14661460 }
14671461
14681462 // Update occupancy grid map in 3D map view and graph view
@@ -1649,7 +1643,7 @@ void MainWindow::createAndAddCloudToMap(int nodeId, const Transform & pose, int
16491643 QColor color = Qt::gray;
16501644 if (mapId >= 0 )
16511645 {
1652- color = (Qt::GlobalColor)(mapId % 12 + 7 );
1646+ color = (Qt::GlobalColor)(mapId+ 3 % 12 + 7 );
16531647 }
16541648 if (!_ui->widget_cloudViewer ->addOrUpdateCloud (cloudName, cloud, pose, color))
16551649 {
@@ -1666,7 +1660,7 @@ void MainWindow::createAndAddCloudToMap(int nodeId, const Transform & pose, int
16661660 QColor color = Qt::gray;
16671661 if (mapId >= 0 )
16681662 {
1669- color = (Qt::GlobalColor)(mapId % 12 + 7 );
1663+ color = (Qt::GlobalColor)(mapId+ 3 % 12 + 7 );
16701664 }
16711665 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
16721666 cloud->resize (iter->getWords3 ().size ());
@@ -1721,12 +1715,12 @@ void MainWindow::createAndAddScanToMap(int nodeId, const Transform & pose, int m
17211715
17221716 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud;
17231717 cloud = util3d::laserScanToPointCloud (depth2D);
1724- QColor color = Qt::red ;
1718+ QColor color = Qt::gray ;
17251719 if (mapId >= 0 )
17261720 {
1727- color = (Qt::GlobalColor)(mapId % 12 + 7 );
1721+ color = (Qt::GlobalColor)(mapId+ 3 % 12 + 7 );
17281722 }
1729- if (!_ui->widget_cloudViewer ->addOrUpdateCloud (scanName, cloud, pose))
1723+ if (!_ui->widget_cloudViewer ->addOrUpdateCloud (scanName, cloud, pose, color ))
17301724 {
17311725 UERROR (" Adding cloud %d to viewer failed!" , nodeId);
17321726 }
0 commit comments