gz-rendering icon indicating copy to clipboard operation
gz-rendering copied to clipboard

[ogre2] Point SetSize API applies globally to all points

Open chapulina opened this issue 4 years ago • 1 comments

Environment

  • OS Version: Ubuntu 20.04
  • Source or binary build? Source, ign-rendering6 branch
  • If this is a GUI or sensor rendering bug, describe your GPU and rendering system. Otherwise delete this section.
    • Rendering plugin: ogre2
    • Generally, mention all circumstances that might affect rendering capabilities:
      • [x] running in Docker/Singularity

Description

  • Expected behavior: Calling SetSize (added on #392) on a LidarVisual / Marker should only affect points on that visual.
  • Actual behavior: That call is modifying the point size for all points in the scene that use point_cloud_point.material.

Steps to reproduce

  1. Update the lidar_visual with this diff to have 2 separate visuals, one with size 5, the other with size 50:
diff

diff --git a/examples/lidar_visual/GlutWindow.cc b/examples/lidar_visual/GlutWindow.cc
index 51f51cdb..5287edab 100644
--- a/examples/lidar_visual/GlutWindow.cc
+++ b/examples/lidar_visual/GlutWindow.cc
@@ -64,7 +64,7 @@ ir::ImagePtr g_image;
 bool g_initContext = false;
 bool g_clear = false;
 std::vector<double> g_lidarData;
-ir::LidarVisualPtr g_lidar;
+std::vector<ir::LidarVisualPtr> g_lidars;
 bool g_lidarVisualUpdateDirty = false;
 bool g_showNonHitting = true;
 LidarVisualType g_lidarVisType = LidarVisualType::LVT_TRIANGLE_STRIPS;
@@ -249,16 +249,19 @@ void updateLidarVisual()
   // change detected due to key press
   if (g_lidarVisualUpdateDirty)
   {
-    if (g_clear == true)
+    for (auto lidar : g_lidars)
     {
-      g_lidar->ClearPoints();
-    }
-    else
-    {
-      g_lidar->SetDisplayNonHitting(g_showNonHitting);
-      g_lidar->SetPoints(g_lidarData);
-      g_lidar->SetType(g_lidarVisType);
-      g_lidar->Update();
+      if (g_clear == true)
+      {
+        lidar->ClearPoints();
+      }
+      else
+      {
+        lidar->SetDisplayNonHitting(g_showNonHitting);
+        lidar->SetPoints(g_lidarData);
+        lidar->SetType(g_lidarVisType);
+        lidar->Update();
+      }
     }
     g_lidarVisualUpdateDirty = false;
     g_clear = false;
@@ -399,7 +402,7 @@ void initCamera(ir::CameraPtr _camera)
 //////////////////////////////////////////////////
 void initLidarVisual(ir::LidarVisualPtr _lidar)
 {
-  g_lidar = _lidar;
+  g_lidars.push_back(_lidar);
 }
 
 //////////////////////////////////////////////////
@@ -457,6 +460,7 @@ void run(std::vector<ir::CameraPtr> _cameras,
 
   initCamera(_cameras[0]);
   initLidarVisual(_nodes[0]);
+  initLidarVisual(_nodes[1]);
   initContext();
   printUsage();
   g_lidarData.clear();
diff --git a/examples/lidar_visual/Main.cc b/examples/lidar_visual/Main.cc
index 71e3eebf..e2d4fec9 100644
--- a/examples/lidar_visual/Main.cc
+++ b/examples/lidar_visual/Main.cc
@@ -239,6 +239,45 @@ LidarVisualPtr createLidar(ScenePtr _scene)
   return lidar;
 }
 
+//////////////////////////////////////////////////
+LidarVisualPtr createLidar2(ScenePtr _scene)
+{
+  // create lidar visual
+  LidarVisualPtr lidar = _scene->CreateLidarVisual();
+  lidar->SetMinHorizontalAngle(hMinAngle);
+  lidar->SetHorizontalRayCount(hRayCount);
+  lidar->SetMaxHorizontalAngle(hMaxAngle);
+  lidar->SetVerticalRayCount(vRayCount);
+  lidar->SetMinVerticalAngle(vMinAngle);
+  lidar->SetMaxVerticalAngle(vMaxAngle);
+  lidar->SetMaxRange(maxRange);
+  lidar->SetMinRange(minRange);
+  lidar->SetSize(50.0);
+
+  // the types can be set as follows:-
+  // LVT_POINTS -> Lidar Points at the range value
+  // LVT_RAY_LINES -> Lines along the lidar sensor to the obstacle
+  // LVT_TRIANGLE_STRIPS -> Coloured triangle strips denoting hitting and
+  // non-hitting parts of the scan
+  lidar->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS);
+  lidar->SetPoints(pts);
+
+  VisualPtr root = _scene->RootVisual();
+  root->AddChild(lidar);
+
+  // set this value to false if only the rays that are hitting another obstacle
+  // are to be displayed.
+  lidar->SetDisplayNonHitting(true);
+
+  lidar->SetWorldPosition(testPose.Pos() + math::Vector3d(1.0, 0.0, 0.0));
+  lidar->SetWorldRotation(testPose.Rot());
+
+  // update lidar visual
+  lidar->Update();
+
+  return lidar;
+}
+
 //////////////////////////////////////////////////
 CameraPtr createCamera(const std::string &_engineName)
 {
@@ -290,6 +329,7 @@ int main(int _argc, char** _argv)
         cameras.push_back(camera);
         sensors.push_back(createGpuRaySensor(camera->Scene()));
         nodes.push_back(createLidar(camera->Scene()));
+        nodes.push_back(createLidar2(camera->Scene()));
       }
     }
     catch (...)
  1. Run the example and press 2 to change to points. You'll see that both visuals have the same size, 50, which was the last set:

image

I believe this is happening because we're modifying the material itself instead of just modifying that instance:

https://github.com/ignitionrobotics/ign-rendering/blob/8e7b7fbbbff519a6fb567efdd4ec08468e8d8f6a/ogre2/src/Ogre2LidarVisual.cc#L481-L485

The same here:

https://github.com/ignitionrobotics/ign-rendering/blob/8e7b7fbbbff519a6fb567efdd4ec08468e8d8f6a/ogre2/src/Ogre2Marker.cc#L110-L114

I think the same happens with the color when set globally for all points (as opposed to per-point like in #494 )

chapulina avatar Nov 30 '21 20:11 chapulina

hmm one thing to try is to clone the material before setting it to marker's ogre item.

iche033 avatar Nov 30 '21 23:11 iche033