File: main.cpp

package info (click to toggle)
dart 6.12.1%2Bdfsg4-12
  • links: PTS, VCS
  • area: main
  • in suites: bookworm
  • size: 57,000 kB
  • sloc: cpp: 269,461; python: 3,911; xml: 1,273; sh: 404; makefile: 30
file content (780 lines) | stat: -rw-r--r-- 25,776 bytes parent folder | download
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
/*
 * Copyright (c) 2011-2021, The DART development contributors
 * All rights reserved.
 *
 * The list of contributors can be found at:
 *   https://github.com/dartsim/dart/blob/master/LICENSE
 *
 * This file is provided under the following "BSD-style" License:
 *   Redistribution and use in source and binary forms, with or
 *   without modification, are permitted provided that the following
 *   conditions are met:
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
 *   CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
 *   INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
 *   MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
 *   DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
 *   CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 *   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
 *   USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 *   AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *   LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *   ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *   POSSIBILITY OF SUCH DAMAGE.
 */

#include <cmath>

#include <dart/dart.hpp>
#include <dart/external/imgui/imgui.h>
#include <dart/gui/osg/osg.hpp>
#include <dart/utils/urdf/urdf.hpp>
#include <dart/utils/utils.hpp>

using namespace dart;
using namespace dart::common;
using namespace dart::dynamics;
using namespace dart::math;

static const std::string& robotName = "KR5";

class PointCloudWorld : public gui::osg::RealTimeWorldNode
{
public:
  enum PointSamplingMode
  {
    SAMPLE_ON_ROBOT = 0,
    SAMPLE_IN_BOX = 1,
  };

  explicit PointCloudWorld(
      simulation::WorldPtr world, dynamics::SkeletonPtr robot)
    : gui::osg::RealTimeWorldNode(std::move(world)),
      mSampleingMode(SAMPLE_ON_ROBOT),
      mRobot(std::move(robot))
  {
    auto pointCloudFrame = mWorld->getSimpleFrame("point cloud");
    auto voxelGridFrame = mWorld->getSimpleFrame("voxel");

    mPointCloudShape = std::dynamic_pointer_cast<dynamics::PointCloudShape>(
        pointCloudFrame->getShape());
    mPointCloudShape->setColorMode(dynamics::PointCloudShape::BIND_PER_POINT);
    mVoxelGridShape = std::dynamic_pointer_cast<dynamics::VoxelGridShape>(
        voxelGridFrame->getShape());

    mPointCloudVisualAspect = pointCloudFrame->getVisualAspect();
    mVoxelGridVisualAspect = voxelGridFrame->getVisualAspect();
    mVoxelGridVisualAspect->show();

    assert(mVoxelGridShape);
  }

  void setPointSamplingMode(PointSamplingMode mode)
  {
    mSampleingMode = mode;
  }

  PointSamplingMode getPointSamplingMode() const
  {
    return mSampleingMode;
  }

  // Triggered at the beginning of each simulation step
  void customPreStep() override
  {
    if (!mRobot)
      return;

    if (!mUpdate)
      return;

    // Set robot pose
    Eigen::VectorXd pos = mRobot->getPositions();
    pos += 0.01 * Eigen::VectorXd::Random(pos.size());
    mRobot->setPositions(pos);

    // Generate point cloud from robot meshes
    octomap::Pointcloud pointCloud;
    auto numPoints = 500u;
    switch (mSampleingMode)
    {
      case SAMPLE_ON_ROBOT:
        pointCloud = generatePointCloudOnRobot(numPoints);
        break;
      case SAMPLE_IN_BOX:
        pointCloud = generatePointCloudInBox(
            numPoints,
            Eigen::Vector3d::Constant(-0.5),
            Eigen::Vector3d::Constant(0.5));
        break;
    }

    // Update sensor position
    static double time = 0.0;
    const double dt = 0.001;
    const double radius = 1.0;
    Eigen::Vector3d center = Eigen::Vector3d(0.0, 0.1, 0.0);
    Eigen::Vector3d sensorPos = center;
    sensorPos[0] = radius * std::sin(time);
    sensorPos[1] = radius * std::cos(time);
    sensorPos[2] = 0.5 + 0.25 * std::sin(time * 2.0);
    time += dt;
    auto sensorFrame = mWorld->getSimpleFrame("sensor");
    assert(sensorFrame);
    sensorFrame->setTranslation(sensorPos);

    // Update point cloud
    mPointCloudShape->setPoints(pointCloud);

    // Update point cloud colors
    auto colors = generatePointCloudColors(pointCloud);
    assert(pointCloud.size() == colors.size());
    mPointCloudShape->setColors(colors);

    // Update voxel
    mVoxelGridShape->updateOccupancy(pointCloud, sensorPos);
  }

  dynamics::VisualAspect* getPointCloudVisualAspect()
  {
    return mPointCloudVisualAspect;
  }

  dynamics::VisualAspect* getVoxelGridVisualAspect()
  {
    return mVoxelGridVisualAspect;
  }

  void setUpdate(bool update)
  {
    mUpdate = update;
  }

  bool getUpdate() const
  {
    return mUpdate;
  }

  std::shared_ptr<dynamics::PointCloudShape> getPointCloudShape()
  {
    return mPointCloudShape;
  }

  std::shared_ptr<const dynamics::PointCloudShape> getPointCloudShape() const
  {
    return mPointCloudShape;
  }

protected:
  octomap::Pointcloud generatePointCloudOnRobot(std::size_t numPoints)
  {
    octomap::Pointcloud pointCloud;
    pointCloud.reserve(numPoints);

    const auto numBodies = mRobot->getNumBodyNodes();
    assert(numBodies > 0);
    while (true)
    {
      const auto bodyIndex
          = math::Random::uniform<std::size_t>(0, numBodies - 1);
      auto body = mRobot->getBodyNode(bodyIndex);
      auto shapeNodes = body->getShapeNodesWith<dynamics::VisualAspect>();
      if (shapeNodes.empty())
        continue;

      const auto shapeIndex
          = math::Random::uniform<std::size_t>(0, shapeNodes.size() - 1);
      auto shapeNode = shapeNodes[shapeIndex];
      auto shape = shapeNode->getShape();
      assert(shape);

      if (!shape->is<dynamics::MeshShape>())
        continue;
      auto mesh = std::static_pointer_cast<dynamics::MeshShape>(shape);

      auto assimpScene = mesh->getMesh();
      assert(assimpScene);

      if (assimpScene->mNumMeshes < 1)
        continue;
      const auto meshIndex
          = math::Random::uniform<std::size_t>(0, assimpScene->mNumMeshes - 1);

      auto assimpMesh = assimpScene->mMeshes[meshIndex];
      auto numVertices = assimpMesh->mNumVertices;

      auto vertexIndex
          = math::Random::uniform<unsigned int>(0, numVertices - 1);
      auto vertex = assimpMesh->mVertices[vertexIndex];

      Eigen::Isometry3d tf = shapeNode->getWorldTransform();
      Eigen::Vector3d eigenVertex
          = Eigen::Vector3f(vertex.x, vertex.y, vertex.z).cast<double>();
      eigenVertex = tf * eigenVertex;

      pointCloud.push_back(
          static_cast<float>(eigenVertex.x()),
          static_cast<float>(eigenVertex.y()),
          static_cast<float>(eigenVertex.z()));

      if (pointCloud.size() == numPoints)
        return pointCloud;
    }
  }

  octomap::Pointcloud generatePointCloudInBox(
      std::size_t numPoints,
      const Eigen::Vector3d& min = Eigen::Vector3d::Constant(-0.5),
      const Eigen::Vector3d& max = Eigen::Vector3d::Constant(0.5))
  {
    octomap::Pointcloud pointCloud;
    pointCloud.reserve(numPoints);

    for (auto i = 0u; i < numPoints; ++i)
    {
      const Eigen::Vector3d point = math::Random::uniform(min, max);
      pointCloud.push_back(
          static_cast<float>(point.x()),
          static_cast<float>(point.y()),
          static_cast<float>(point.z()));
    }

    return pointCloud;
  }

  std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d>>
  generatePointCloudColors(const octomap::Pointcloud& pointCloud)
  {
    const auto& points = mPointCloudShape->getPoints();
    double minZ = std::numeric_limits<double>::max();
    double maxZ = std::numeric_limits<double>::min();
    for (const auto& point : points)
    {
      minZ = std::min(minZ, point.z());
      maxZ = std::max(maxZ, point.z());
    }
    double diffZ
        = std::max(std::abs(maxZ - minZ), std::numeric_limits<double>::min());

    std::vector<Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d>>
        colors;
    colors.reserve(pointCloud.size());
    for (const auto& point : pointCloud)
    {
      float r
          = (point.z() - static_cast<float>(minZ)) / static_cast<float>(diffZ);
      float g = 0.0f;
      float b = 1.f - r;
      r = math::clip(r, 0.1f, 0.9f);
      g = math::clip(g, 0.1f, 0.9f);
      b = math::clip(b, 0.1f, 0.9f);
      colors.emplace_back(Eigen::Vector4f(r, g, b, 0.75).cast<double>());
    }

    return colors;
  }

  PointSamplingMode mSampleingMode;

  SkeletonPtr mRobot;

  std::shared_ptr<dynamics::PointCloudShape> mPointCloudShape;
  std::shared_ptr<dynamics::VoxelGridShape> mVoxelGridShape;

  dynamics::VisualAspect* mPointCloudVisualAspect;
  dynamics::VisualAspect* mVoxelGridVisualAspect;

  bool mUpdate{true};
};

class PointCloudWidget : public dart::gui::osg::ImGuiWidget
{
public:
  PointCloudWidget(
      dart::gui::osg::ImGuiViewer* viewer,
      PointCloudWorld* node,
      gui::osg::GridVisual* grid)
    : mViewer(viewer), mNode(node), mGrid(grid)
  {
    // Do nothing
  }

  void render() override
  {
    ImGui::SetNextWindowPos(ImVec2(10, 20));
    ImGui::SetNextWindowSize(ImVec2(360, 600));
    ImGui::SetNextWindowBgAlpha(0.5f);
    if (!ImGui::Begin(
            "Point Cloud & Voxel Grid Demo",
            nullptr,
            ImGuiWindowFlags_MenuBar | ImGuiWindowFlags_HorizontalScrollbar))
    {
      // Early out if the window is collapsed, as an optimization.
      ImGui::End();
      return;
    }

    // Menu
    if (ImGui::BeginMenuBar())
    {
      if (ImGui::BeginMenu("Menu"))
      {
        if (ImGui::MenuItem("Exit"))
          mViewer->setDone(true);
        ImGui::EndMenu();
      }
      if (ImGui::BeginMenu("Help"))
      {
        if (ImGui::MenuItem("About DART"))
          mViewer->showAbout();
        ImGui::EndMenu();
      }
      ImGui::EndMenuBar();
    }

    ImGui::Text("Point cloud and voxel grid rendering example");
    ImGui::Spacing();
    ImGui::TextWrapped(
        "The robot is moving by random joint velocities. The small blue boxes "
        "and orange boxes represent point cloud and voxel grid, respectively. "
        "The moving red sphere represents the sensor origin that generates the "
        "point cloud.");

    if (ImGui::CollapsingHeader("Help"))
    {
      ImGui::PushTextWrapPos(ImGui::GetCursorPos().x + 320);
      ImGui::Text("User Guid:\n");
      ImGui::Text("%s", mViewer->getInstructions().c_str());
      ImGui::PopTextWrapPos();
    }

    if (ImGui::CollapsingHeader("Simulation", ImGuiTreeNodeFlags_DefaultOpen))
    {
      int e = mViewer->isSimulating() ? 0 : 1;
      if (mViewer->isAllowingSimulation())
      {
        if (ImGui::RadioButton("Play", &e, 0) && !mViewer->isSimulating())
          mViewer->simulate(true);
        ImGui::SameLine();
        if (ImGui::RadioButton("Pause", &e, 1) && mViewer->isSimulating())
          mViewer->simulate(false);
      }

      int robotUpdate = mNode->getUpdate() ? 0 : 1;
      if (ImGui::RadioButton("Run Robot Updating", &robotUpdate, 0))
        mNode->setUpdate(true);
      ImGui::SameLine();
      if (ImGui::RadioButton("Stop Robot Updating", &robotUpdate, 1))
        mNode->setUpdate(false);

      int samplingMode
          = mNode->getPointSamplingMode() == PointCloudWorld::SAMPLE_ON_ROBOT
                ? 0
                : 1;
      if (ImGui::RadioButton("Sample on robot", &samplingMode, 0))
        mNode->setPointSamplingMode(PointCloudWorld::SAMPLE_ON_ROBOT);
      ImGui::SameLine();
      if (ImGui::RadioButton("Sample in box", &samplingMode, 1))
        mNode->setPointSamplingMode(PointCloudWorld::SAMPLE_IN_BOX);
    }

    if (ImGui::CollapsingHeader("View", ImGuiTreeNodeFlags_DefaultOpen))
    {
      if (mViewer->isAllowingSimulation())
      {
        // Point cloud settings
        bool pcShow = !mNode->getPointCloudVisualAspect()->isHidden();
        if (ImGui::Checkbox("Point Cloud", &pcShow))
        {
          if (pcShow)
            mNode->getPointCloudVisualAspect()->show();
          else
            mNode->getPointCloudVisualAspect()->hide();
        }

        if (pcShow)
        {
          auto pointCloudShape = mNode->getPointCloudShape();

          const char* colorModeItems[]
              = {"Use shape color", "Bind overall", "Bind per point"};
          int colorMode = pointCloudShape->getColorMode();
          if (ImGui::Combo(
                  "Color Mode",
                  &colorMode,
                  colorModeItems,
                  IM_ARRAYSIZE(colorModeItems)))
          {
            if (colorMode == 0)
            {
              pointCloudShape->setColorMode(
                  dynamics::PointCloudShape::USE_SHAPE_COLOR);
            }
            else if (colorMode == 1)
            {
              pointCloudShape->setColorMode(
                  dynamics::PointCloudShape::BIND_OVERALL);
            }
            else if (colorMode == 2)
            {
              pointCloudShape->setColorMode(
                  dynamics::PointCloudShape::BIND_PER_POINT);
            }
          }
          if (colorMode == 0)
          {
            auto visual = mNode->getPointCloudVisualAspect();
            Eigen::Vector4d rgba = visual->getRGBA();
            float color_rbga[4];
            color_rbga[0] = static_cast<float>(rgba[0]);
            color_rbga[1] = static_cast<float>(rgba[1]);
            color_rbga[2] = static_cast<float>(rgba[2]);
            color_rbga[3] = static_cast<float>(rgba[3]);
            if (ImGui::ColorEdit4("Color", color_rbga))
            {
              rgba[0] = static_cast<double>(color_rbga[0]);
              rgba[1] = static_cast<double>(color_rbga[1]);
              rgba[2] = static_cast<double>(color_rbga[2]);
              rgba[3] = static_cast<double>(color_rbga[3]);
              visual->setRGBA(rgba);
            }
          }

          const char* pointShapeTypeItems[]
              = {"Box", "Billboard Square", "Billboard Circle", "Point"};
          int pointShapeType = pointCloudShape->getPointShapeType();
          if (ImGui::Combo(
                  "Point Shape Type",
                  &pointShapeType,
                  pointShapeTypeItems,
                  IM_ARRAYSIZE(pointShapeTypeItems)))
          {
            if (pointShapeType == 0)
            {
              pointCloudShape->setPointShapeType(
                  dynamics::PointCloudShape::BOX);
            }
            else if (pointShapeType == 1)
            {
              pointCloudShape->setPointShapeType(
                  dynamics::PointCloudShape::BILLBOARD_SQUARE);
            }
            else if (pointShapeType == 2)
            {
              pointCloudShape->setPointShapeType(
                  dynamics::PointCloudShape::BILLBOARD_CIRCLE);
            }
            else if (pointShapeType == 3)
            {
              pointCloudShape->setPointShapeType(
                  dynamics::PointCloudShape::POINT);
            }
          }

          float visualSize
              = static_cast<float>(pointCloudShape->getVisualSize());
          if (ImGui::InputFloat(
                  "Visual Size", &visualSize, 0.01f, 0.02f, "%.2f"))
          {
            if (visualSize < 0.01f)
              visualSize = 0.01f;
            pointCloudShape->setVisualSize(static_cast<double>(visualSize));
          }
        }

        ::ImGui::Separator();

        // Voxel settings
        bool vgShow = !mNode->getVoxelGridVisualAspect()->isHidden();
        if (ImGui::Checkbox("Voxel Grid", &vgShow))
        {
          if (vgShow)
            mNode->getVoxelGridVisualAspect()->show();
          else
            mNode->getVoxelGridVisualAspect()->hide();
        }
        if (vgShow)
        {
          auto visual = mNode->getVoxelGridVisualAspect();
          Eigen::Vector4d rgba = visual->getRGBA();
          float color_rbga[4];
          color_rbga[0] = static_cast<float>(rgba[0]);
          color_rbga[1] = static_cast<float>(rgba[1]);
          color_rbga[2] = static_cast<float>(rgba[2]);
          color_rbga[3] = static_cast<float>(rgba[3]);
          if (ImGui::ColorEdit4("Voxel grid color", color_rbga))
          {
            rgba[0] = static_cast<double>(color_rbga[0]);
            rgba[1] = static_cast<double>(color_rbga[1]);
            rgba[2] = static_cast<double>(color_rbga[2]);
            rgba[3] = static_cast<double>(color_rbga[3]);
            visual->setRGBA(rgba);
          }
        }
      }

      if (ImGui::CollapsingHeader("Grid", ImGuiTreeNodeFlags_None))
      {
        assert(mGrid);
        ImGui::Text("Grid");

        bool display = mGrid->isDisplayed();
        if (ImGui::Checkbox("Show", &display))
          mGrid->display(display);

        if (display)
        {
          int e = static_cast<int>(mGrid->getPlaneType());
          if (mViewer->isAllowingSimulation())
          {
            if (ImGui::RadioButton("XY-Plane", &e, 0))
              mGrid->setPlaneType(gui::osg::GridVisual::PlaneType::XY);
            ImGui::SameLine();
            if (ImGui::RadioButton("YZ-Plane", &e, 1))
              mGrid->setPlaneType(gui::osg::GridVisual::PlaneType::YZ);
            ImGui::SameLine();
            if (ImGui::RadioButton("ZX-Plane", &e, 2))
              mGrid->setPlaneType(gui::osg::GridVisual::PlaneType::ZX);
          }

          static Eigen::Vector3f offset;
          ImGui::Columns(3);
          offset = mGrid->getOffset().cast<float>();
          if (ImGui::InputFloat("X", &offset[0], 0.1f, 0.5f, "%.1f"))
            mGrid->setOffset(offset.cast<double>());
          ImGui::NextColumn();
          if (ImGui::InputFloat("Y", &offset[1], 0.1f, 0.5f, "%.1f"))
            mGrid->setOffset(offset.cast<double>());
          ImGui::NextColumn();
          if (ImGui::InputFloat("Z", &offset[2], 0.1f, 0.5f, "%.1f"))
            mGrid->setOffset(offset.cast<double>());
          ImGui::Columns(1);

          static int cellCount;
          cellCount = static_cast<int>(mGrid->getNumCells());
          if (ImGui::InputInt("Line Count", &cellCount, 1, 5))
          {
            if (cellCount < 0)
              cellCount = 0;
            mGrid->setNumCells(static_cast<std::size_t>(cellCount));
          }

          static float cellStepSize;
          cellStepSize = static_cast<float>(mGrid->getMinorLineStepSize());
          if (ImGui::InputFloat("Line Step Size", &cellStepSize, 0.001f, 0.1f))
          {
            mGrid->setMinorLineStepSize(static_cast<double>(cellStepSize));
          }

          static int minorLinesPerMajorLine;
          minorLinesPerMajorLine
              = static_cast<int>(mGrid->getNumMinorLinesPerMajorLine());
          if (ImGui::InputInt(
                  "Minor Lines per Major Line", &minorLinesPerMajorLine, 1, 5))
          {
            if (minorLinesPerMajorLine < 0)
              minorLinesPerMajorLine = 0;
            mGrid->setNumMinorLinesPerMajorLine(
                static_cast<std::size_t>(minorLinesPerMajorLine));
          }

          static float axisLineWidth;
          axisLineWidth = mGrid->getAxisLineWidth();
          if (ImGui::InputFloat(
                  "Axis Line Width", &axisLineWidth, 1.f, 2.f, "%.0f"))
          {
            mGrid->setAxisLineWidth(axisLineWidth);
          }

          static float majorLineWidth;
          majorLineWidth = mGrid->getMajorLineWidth();
          if (ImGui::InputFloat(
                  "Major Line Width", &majorLineWidth, 1.f, 2.f, "%.0f"))
          {
            mGrid->setMajorLineWidth(majorLineWidth);
          }

          static float majorColor[3];
          auto internalmajorColor = mGrid->getMajorLineColor();
          majorColor[0] = static_cast<float>(internalmajorColor.x());
          majorColor[1] = static_cast<float>(internalmajorColor.y());
          majorColor[2] = static_cast<float>(internalmajorColor.z());
          if (ImGui::ColorEdit3("Major Line Color", majorColor))
          {
            internalmajorColor[0] = static_cast<double>(majorColor[0]);
            internalmajorColor[1] = static_cast<double>(majorColor[1]);
            internalmajorColor[2] = static_cast<double>(majorColor[2]);
            mGrid->setMajorLineColor(internalmajorColor);
          }

          static float minorLineWidth;
          minorLineWidth = mGrid->getMinorLineWidth();
          if (ImGui::InputFloat(
                  "Minor Line Width", &minorLineWidth, 1.f, 2.f, "%.0f"))
          {
            mGrid->setMinorLineWidth(minorLineWidth);
          }

          float minorColor[3];
          auto internalMinorColor = mGrid->getMinorLineColor();
          minorColor[0] = static_cast<float>(internalMinorColor.x());
          minorColor[1] = static_cast<float>(internalMinorColor.y());
          minorColor[2] = static_cast<float>(internalMinorColor.z());
          if (ImGui::ColorEdit3("Minor Line Color", minorColor))
          {
            internalMinorColor[0] = static_cast<double>(minorColor[0]);
            internalMinorColor[1] = static_cast<double>(minorColor[1]);
            internalMinorColor[2] = static_cast<double>(minorColor[2]);
            mGrid->setMinorLineColor(internalMinorColor);
          }
        }
      }
    }

    ImGui::End();
  }

protected:
  osg::ref_ptr<dart::gui::osg::ImGuiViewer> mViewer;
  osg::ref_ptr<PointCloudWorld> mNode;
  osg::ref_ptr<gui::osg::GridVisual> mGrid;
};

dynamics::SkeletonPtr createRobot(const std::string& name)
{
  auto urdfParser = dart::utils::DartLoader();

  // Load the robot
  auto robot
      = urdfParser.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf");

  // Rotate the robot so that z is upwards (default transform is not Identity)
  robot->getJoint(0)->setTransformFromParentBodyNode(
      Eigen::Isometry3d::Identity());

  robot->setName(name);

  return robot;
}

dynamics::SkeletonPtr createGround()
{
  auto urdfParser = dart::utils::DartLoader();

  auto ground = urdfParser.parseSkeleton("dart://sample/urdf/KR5/ground.urdf");

  // Rotate and move the ground so that z is upwards
  Eigen::Isometry3d ground_tf
      = ground->getJoint(0)->getTransformFromParentBodyNode();
  ground_tf.pretranslate(Eigen::Vector3d(0, 0, 0.5));
  ground_tf.rotate(
      Eigen::AngleAxisd(constantsd::pi() / 2, Eigen::Vector3d(1, 0, 0)));
  ground->getJoint(0)->setTransformFromParentBodyNode(ground_tf);

  return ground;
}

dynamics::SimpleFramePtr createVoxelFrame(double resolution = 0.01)
{
  auto voxelShape
      = ::std::make_shared<dart::dynamics::VoxelGridShape>(resolution);
  auto voxelFrame = ::dart::dynamics::SimpleFrame::createShared(
      dart::dynamics::Frame::World());
  voxelFrame->setName("voxel");
  voxelFrame->setShape(voxelShape);
  auto visualAspect = voxelFrame->createVisualAspect();
  visualAspect->setRGBA(Color::Orange(0.5));

  return voxelFrame;
}

dynamics::SimpleFramePtr createPointCloudFrame()
{
  auto pointCloudShape
      = ::std::make_shared<::dart::dynamics::PointCloudShape>();
  pointCloudShape->setPointShapeType(::dart::dynamics::PointCloudShape::BOX);
  auto pointCloudFrame = ::dart::dynamics::SimpleFrame::createShared(
      dart::dynamics::Frame::World());
  pointCloudFrame->setName("point cloud");
  pointCloudFrame->setShape(pointCloudShape);
  auto visualAspect = pointCloudFrame->createVisualAspect();
  visualAspect->setRGB(Color::Blue());

  return pointCloudFrame;
}

dynamics::SimpleFramePtr createSensorFrame()
{
  auto sphereShape = ::std::make_shared<dart::dynamics::SphereShape>(0.05);
  auto sensorFrame = ::dart::dynamics::SimpleFrame::createShared(
      dart::dynamics::Frame::World());
  sensorFrame->setName("sensor");
  sensorFrame->setShape(sphereShape);
  auto visualAspect = sensorFrame->createVisualAspect();
  visualAspect->setRGB(Color::Red());

  return sensorFrame;
}

int main()
{
  auto world = dart::simulation::World::create();
  world->setGravity(Eigen::Vector3d::Zero());

  auto robot = createRobot(robotName);
  world->addSkeleton(robot);

  auto ground = createGround();
  world->addSkeleton(ground);

  auto pointCloud = createPointCloudFrame();
  world->addSimpleFrame(pointCloud);

  auto voxel = createVoxelFrame(0.05);
  world->addSimpleFrame(voxel);

  auto sensor = createSensorFrame();
  world->addSimpleFrame(sensor);

  // Create an instance of our customized WorldNode
  ::osg::ref_ptr<PointCloudWorld> node = new PointCloudWorld(world, robot);

  // Create the Viewer instance
  osg::ref_ptr<dart::gui::osg::ImGuiViewer> viewer
      = new dart::gui::osg::ImGuiViewer();
  viewer->addWorldNode(node);
  viewer->simulate(true);

  // Create grid
  ::osg::ref_ptr<gui::osg::GridVisual> grid = new gui::osg::GridVisual();

  // Add control widget for atlas
  viewer->getImGuiHandler()->addWidget(
      std::make_shared<PointCloudWidget>(viewer, node, grid));

  viewer->addAttachment(grid);

  // Print out instructions
  std::cout << viewer->getInstructions() << std::endl;

  // Set up the window to be 1280x720 pixels
  viewer->setUpViewInWindow(0, 0, 1280, 720);

  viewer->getCameraManipulator()->setHomePosition(
      ::osg::Vec3(2.57f, 3.14f, 1.64f),
      ::osg::Vec3(0.00f, 0.00f, 0.30f),
      ::osg::Vec3(-0.24f, -0.25f, 0.94f));
  // We need to re-dirty the CameraManipulator by passing it into the viewer
  // again, so that the viewer knows to update its HomePosition setting
  viewer->setCameraManipulator(viewer->getCameraManipulator());

  // Begin the application loop
  viewer->run();
}