Skip to content

Commit 9ef3ce2

Browse files
committed
Merge branch 'gz-sim-executable' of github.com:sauk2/gz-sim into gz-sim-executable
Signed-off-by: Saurabh Kamat <kamatsaurabh01@gmail.com>
2 parents 3cfa88b + 6c69826 commit 9ef3ce2

File tree

5 files changed

+345
-74
lines changed

5 files changed

+345
-74
lines changed
Lines changed: 108 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
/*
2+
* Copyright (C) 2024 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#ifndef GZ_SIM_COMPONENTS_RAYCASTDATA_HH_
19+
#define GZ_SIM_COMPONENTS_RAYCASTDATA_HH_
20+
21+
#include <gz/math/Vector3.hh>
22+
#include <gz/sim/components/Factory.hh>
23+
#include <gz/sim/components/Component.hh>
24+
#include <gz/sim/components/Serialization.hh>
25+
#include <gz/sim/config.hh>
26+
27+
#include <istream>
28+
#include <ostream>
29+
#include <vector>
30+
31+
namespace gz
32+
{
33+
namespace sim
34+
{
35+
// Inline bracket to help doxygen filtering.
36+
inline namespace GZ_SIM_VERSION_NAMESPACE {
37+
namespace components
38+
{
39+
/// \brief A struct that holds the information of a ray.
40+
struct RayInfo
41+
{
42+
/// \brief Starting point of the ray in entity frame
43+
gz::math::Vector3d start;
44+
45+
/// \brief Ending point of the ray in entity frame
46+
gz::math::Vector3d end;
47+
};
48+
49+
/// \brief A struct that holds the result of a raycasting operation.
50+
struct RaycastResultInfo
51+
{
52+
/// \brief The hit point in entity frame
53+
gz::math::Vector3d point;
54+
55+
/// \brief The fraction of the ray length at the intersection/hit point.
56+
double fraction;
57+
58+
/// \brief The normal at the hit point in entity frame
59+
gz::math::Vector3d normal;
60+
};
61+
62+
/// @brief A struct that holds the raycasting data, including ray and results
63+
struct RaycastDataInfo
64+
{
65+
/// @brief The rays to cast from the entity.
66+
std::vector<RayInfo> rays;
67+
68+
/// @brief The results of the raycasting.
69+
std::vector<RaycastResultInfo> results;
70+
};
71+
}
72+
73+
namespace serializers
74+
{
75+
/// \brief Specialization of DefaultSerializer for RaycastDataInfo
76+
template<> class DefaultSerializer<components::RaycastDataInfo>
77+
{
78+
public: static std::ostream &Serialize(
79+
std::ostream &_out, const components::RaycastDataInfo &)
80+
{
81+
return _out;
82+
}
83+
84+
public: static std::istream &Deserialize(
85+
std::istream &_in, components::RaycastDataInfo &)
86+
{
87+
return _in;
88+
}
89+
};
90+
}
91+
92+
namespace components
93+
{
94+
/// \brief A component type that contains the rays traced from an entity
95+
/// into a physics world, along with the results of the raycasting operation.
96+
///
97+
/// This component is primarily used for applications that require raycasting.
98+
/// The target application defines the rays, and the physics system plugin
99+
/// updates the raycasting results during each update loop.
100+
using RaycastData = Component<RaycastDataInfo, class RaycastDataTag,
101+
serializers::DefaultSerializer<RaycastDataInfo>>;
102+
103+
GZ_SIM_REGISTER_COMPONENT("gz_sim_components.RaycastData", RaycastData)
104+
}
105+
}
106+
}
107+
}
108+
#endif // GZ_SIM_COMPONENTS_RAYCASTDATA_HH_

src/gui/plugins/visualize_lidar/VisualizeLidar.cc

Lines changed: 26 additions & 73 deletions
Original file line numberDiff line numberDiff line change
@@ -17,13 +17,11 @@
1717

1818
#include "VisualizeLidar.hh"
1919

20+
#include <mutex>
2021
#include <string>
2122
#include <utility>
2223
#include <vector>
2324

24-
#include <sdf/Link.hh>
25-
#include <sdf/Model.hh>
26-
2725
#include <gz/common/Console.hh>
2826
#include <gz/common/Profiler.hh>
2927

@@ -78,18 +76,11 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
7876
/// \brief Pointer to LidarVisual
7977
public: rendering::LidarVisualPtr lidar;
8078

81-
/// \brief Visual type for lidar visual
82-
public: rendering::LidarVisualType visualType{
83-
rendering::LidarVisualType::LVT_TRIANGLE_STRIPS};
84-
85-
/// \brief LaserScan message from sensor
86-
public: msgs::LaserScan msg;
87-
8879
/// \brief Pose of the lidar visual
8980
public: math::Pose3d lidarPose{math::Pose3d::Zero};
9081

9182
/// \brief Topic name to subscribe
92-
public: std::string topicName{""};
83+
public: std::string topicName;
9384

9485
/// \brief List of topics publishing LaserScan messages.
9586
public: QStringList topicList;
@@ -109,6 +100,10 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
109100
/// maxVisualRange
110101
public: std::mutex serviceMutex;
111102

103+
/// \brief Visual type for lidar visual
104+
public: rendering::LidarVisualType visualType{
105+
rendering::LidarVisualType::LVT_TRIANGLE_STRIPS};
106+
112107
/// \brief Initialization flag
113108
public: bool initialized{false};
114109

@@ -145,42 +140,9 @@ VisualizeLidar::~VisualizeLidar()
145140
/////////////////////////////////////////////////
146141
void VisualizeLidar::LoadLidar()
147142
{
148-
auto loadedEngNames = rendering::loadedEngines();
149-
if (loadedEngNames.empty())
150-
return;
151-
152-
// assume there is only one engine loaded
153-
auto engineName = loadedEngNames[0];
154-
if (loadedEngNames.size() > 1)
155-
{
156-
gzdbg << "More than one engine is available. "
157-
<< "VisualizeLidar plugin will use engine ["
158-
<< engineName << "]" << std::endl;
159-
}
160-
auto engine = rendering::engine(engineName);
161-
if (!engine)
162-
{
163-
gzerr << "Internal error: failed to load engine [" << engineName
164-
<< "]. VisualizeLidar plugin won't work." << std::endl;
165-
return;
166-
}
167-
168-
if (engine->SceneCount() == 0)
169-
return;
170-
171-
// assume there is only one scene
172-
// load scene
173-
auto scene = engine->SceneByIndex(0);
143+
auto scene = rendering::sceneFromFirstRenderEngine();
174144
if (!scene)
175-
{
176-
gzerr << "Internal error: scene is null." << std::endl;
177-
return;
178-
}
179-
180-
if (!scene->IsInitialized())
181-
{
182145
return;
183-
}
184146

185147
// Create lidar visual
186148
gzdbg << "Creating lidar visual" << std::endl;
@@ -190,7 +152,7 @@ void VisualizeLidar::LoadLidar()
190152
if (!this->dataPtr->lidar)
191153
{
192154
gzwarn << "Failed to create lidar, visualize lidar plugin won't work."
193-
<< std::endl;
155+
<< std::endl;
194156

195157
scene->DestroyVisual(this->dataPtr->lidar);
196158

@@ -363,7 +325,7 @@ void VisualizeLidar::OnTopic(const QString &_topicName)
363325
!this->dataPtr->node.Unsubscribe(this->dataPtr->topicName))
364326
{
365327
gzerr << "Unable to unsubscribe from topic ["
366-
<< this->dataPtr->topicName <<"]" <<std::endl;
328+
<< this->dataPtr->topicName <<"]" <<std::endl;
367329
}
368330
this->dataPtr->topicName = topic;
369331

@@ -376,7 +338,7 @@ void VisualizeLidar::OnTopic(const QString &_topicName)
376338
&VisualizeLidar::OnScan, this))
377339
{
378340
gzerr << "Unable to subscribe to topic ["
379-
<< this->dataPtr->topicName << "]\n";
341+
<< this->dataPtr->topicName << "]\n";
380342
return;
381343
}
382344
this->dataPtr->visualDirty = false;
@@ -398,7 +360,7 @@ void VisualizeLidar::DisplayVisual(bool _value)
398360
std::lock_guard<std::mutex> lock(this->dataPtr->serviceMutex);
399361
this->dataPtr->lidar->SetVisible(_value);
400362
gzmsg << "Lidar Visual Display " << ((_value) ? "ON." : "OFF.")
401-
<< std::endl;
363+
<< std::endl;
402364
}
403365

404366
/////////////////////////////////////////////////
@@ -412,12 +374,12 @@ void VisualizeLidar::OnRefresh()
412374
// Get updated list
413375
std::vector<std::string> allTopics;
414376
this->dataPtr->node.TopicList(allTopics);
415-
for (auto topic : allTopics)
377+
for (const auto &topic : allTopics)
416378
{
417379
std::vector<transport::MessagePublisher> publishers;
418380
std::vector<transport::MessagePublisher> subscribers;
419381
this->dataPtr->node.TopicInfo(topic, publishers, subscribers);
420-
for (auto pub : publishers)
382+
for (const auto &pub : publishers)
421383
{
422384
if (pub.MsgTypeName() == "gz.msgs.LaserScan")
423385
{
@@ -426,7 +388,7 @@ void VisualizeLidar::OnRefresh()
426388
}
427389
}
428390
}
429-
if (this->dataPtr->topicList.size() > 0)
391+
if (!this->dataPtr->topicList.empty())
430392
{
431393
this->OnTopic(this->dataPtr->topicList.at(0));
432394
}
@@ -453,35 +415,26 @@ void VisualizeLidar::OnScan(const msgs::LaserScan &_msg)
453415
std::lock_guard<std::mutex> lock(this->dataPtr->serviceMutex);
454416
if (this->dataPtr->initialized)
455417
{
456-
this->dataPtr->msg = std::move(_msg);
457-
this->dataPtr->lidar->SetVerticalRayCount(
458-
this->dataPtr->msg.vertical_count());
459-
this->dataPtr->lidar->SetHorizontalRayCount(
460-
this->dataPtr->msg.count());
461-
this->dataPtr->lidar->SetMinHorizontalAngle(
462-
this->dataPtr->msg.angle_min());
463-
this->dataPtr->lidar->SetMaxHorizontalAngle(
464-
this->dataPtr->msg.angle_max());
465-
this->dataPtr->lidar->SetMinVerticalAngle(
466-
this->dataPtr->msg.vertical_angle_min());
467-
this->dataPtr->lidar->SetMaxVerticalAngle(
468-
this->dataPtr->msg.vertical_angle_max());
418+
this->dataPtr->lidar->SetVerticalRayCount(_msg.vertical_count());
419+
this->dataPtr->lidar->SetHorizontalRayCount(_msg.count());
420+
this->dataPtr->lidar->SetMinHorizontalAngle(_msg.angle_min());
421+
this->dataPtr->lidar->SetMaxHorizontalAngle(_msg.angle_max());
422+
this->dataPtr->lidar->SetMinVerticalAngle(_msg.vertical_angle_min());
423+
this->dataPtr->lidar->SetMaxVerticalAngle(_msg.vertical_angle_max());
469424

470425
this->dataPtr->lidar->SetPoints(std::vector<double>(
471-
this->dataPtr->msg.ranges().begin(),
472-
this->dataPtr->msg.ranges().end()));
426+
_msg.ranges().begin(),
427+
_msg.ranges().end()));
473428

474-
if (!math::equal(this->dataPtr->maxVisualRange,
475-
this->dataPtr->msg.range_max()))
429+
if (!math::equal(this->dataPtr->maxVisualRange, _msg.range_max()))
476430
{
477-
this->dataPtr->maxVisualRange = this->dataPtr->msg.range_max();
431+
this->dataPtr->maxVisualRange = _msg.range_max();
478432
this->dataPtr->lidar->SetMaxRange(this->dataPtr->maxVisualRange);
479433
this->MaxRangeChanged();
480434
}
481-
if (!math::equal(this->dataPtr->minVisualRange,
482-
this->dataPtr->msg.range_min()))
435+
if (!math::equal(this->dataPtr->minVisualRange, _msg.range_min()))
483436
{
484-
this->dataPtr->minVisualRange = this->dataPtr->msg.range_min();
437+
this->dataPtr->minVisualRange = _msg.range_min();
485438
this->dataPtr->lidar->SetMinRange(this->dataPtr->minVisualRange);
486439
this->MinRangeChanged();
487440
}

src/gui/plugins/visualize_lidar/VisualizeLidar.hh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ inline namespace GZ_SIM_VERSION_NAMESPACE
3535

3636
/// \brief Visualize the LaserScan message returned by the sensors. Use the
3737
/// checkbox to turn visualization of non-hitting rays on or off and
38-
/// the textfield to select the message to be visualised. The combobox is
38+
/// the textfield to select the message to be visualized. The combobox is
3939
/// used to select the type of visual for the sensor data.
4040
class VisualizeLidar : public gz::sim::GuiSystem
4141
{

0 commit comments

Comments
 (0)