Skip to content

Commit

Permalink
Minor fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
mihirk284 committed Jul 20, 2020
1 parent 882539f commit 600560e
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 1 deletion.
2 changes: 1 addition & 1 deletion ogre/include/ignition/rendering/ogre/OgreLidarVisual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace ignition
public: virtual void PreRender() override;

// Documentation inherited.
public: virtual void Destroy();
public: virtual void Destroy() override;

// Documentation inherited
public: virtual void Update() override;
Expand Down
26 changes: 26 additions & 0 deletions test/integration/lidar_visual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,26 @@ void LidarVisualTest::Configure(const std::string &_renderEngine)
ignition::math::Pose3d offset(1.5, 3.6, 2.9, 1.1, -5.3, -2.9);
lidarVis->SetOffset(offset);
EXPECT_EQ(lidarVis->Offset(), offset);

lidarVis->SetType(LVT_NONE);
EXPECT_EQ(lidarVis->Type(), LVT_NONE);
lidarVis->SetType(LVT_POINTS);
EXPECT_EQ(lidarVis->Type(), LVT_POINTS);
lidarVis->SetType(LVT_POINTS);
EXPECT_EQ(lidarVis->Type(), LVT_POINTS);
lidarVis->SetType(LVT_TRIANGLE_STRIPS);
EXPECT_EQ(lidarVis->Type(), LVT_TRIANGLE_STRIPS);

lidarVis->SetDisplayNonHitting(true);
EXPECT_EQ(lidarVis->DisplayNonHitting(), true);
lidarVis->SetDisplayNonHitting(false);
EXPECT_EQ(lidarVis->DisplayNonHitting(), false);

std::vector<double> pts = {2, 14, 15, 3, 5, 10, 3};
lidarVis->SetPoints(pts);
EXPECT_EQ(lidarVis->PointCount(), pts.size());
lidarVis->ClearPoints();
EXPECT_EQ(lidarVis->PointCount(), 0u);
}

// Clean up
Expand Down Expand Up @@ -216,6 +236,8 @@ void LidarVisualTest::RaysUnitBox(const std::string &_renderEngine)
lidarVis->SetMaxHorizontalAngle(hMaxAngle);
lidarVis->SetHorizontalRayCount(hRayCount);
lidarVis->SetVerticalRayCount(vRayCount);
lidarVis->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS);
lidarVis->SetDisplayNonHitting(true);
root->AddChild(lidarVis);

// Create a second ray caster rotated
Expand Down Expand Up @@ -244,6 +266,8 @@ void LidarVisualTest::RaysUnitBox(const std::string &_renderEngine)
lidarVis2->SetMaxHorizontalAngle(hMaxAngle);
lidarVis2->SetHorizontalRayCount(hRayCount);
lidarVis2->SetVerticalRayCount(vRayCount);
lidarVis2->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS);
lidarVis2->SetDisplayNonHitting(true);
root->AddChild(lidarVis2);

// Create testing boxes
Expand Down Expand Up @@ -463,6 +487,8 @@ void LidarVisualTest::LaserVertical(const std::string &_renderEngine)
lidarVis->SetMaxHorizontalAngle(hMaxAngle);
lidarVis->SetHorizontalRayCount(hRayCount);
lidarVis->SetVerticalRayCount(vRayCount);
lidarVis->SetType(LidarVisualType::LVT_TRIANGLE_STRIPS);
lidarVis->SetDisplayNonHitting(true);
root->AddChild(lidarVis);

// Create testing boxes
Expand Down

0 comments on commit 600560e

Please sign in to comment.