Skip to content

Commit 01235ee

Browse files
committed
fix: default needsRaycast to true, add subscriber in RaycastResultsProcessed
- Default RaycastDataInfo::needsRaycast to true so that manually-created RaycastData components are processed by Physics without needing to know about the optimization flag. The CpuLidar system already explicitly manages the flag each step. - Add a topic subscriber in the RaycastResultsProcessed test so that HasConnections() returns true and the CpuLidar system requests raycasts. Generated-by: Amp <amp@ampcode.com> Signed-off-by: Alexis Pojomovsky <apojomovsky@gmail.com>
1 parent 26a2b6a commit 01235ee

File tree

2 files changed

+9
-2
lines changed

2 files changed

+9
-2
lines changed

include/gz/sim/components/RaycastData.hh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ struct RaycastDataInfo
6969
std::vector<RaycastResultInfo> results;
7070

7171
/// @brief Whether the sensor needs fresh raycast results this step.
72-
bool needsRaycast = false;
72+
bool needsRaycast = true;
7373
};
7474
}
7575

test/integration/cpu_lidar_system.cc

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ static constexpr int kDiscoveryIterations = 10;
5757
/// \brief Iterations for raycast data validity test
5858
static constexpr int kRaycastDataIterations = 10;
5959
/// \brief Iterations for raycast results processing test
60-
static constexpr int kRaycastResultsIterations = 20;
60+
static constexpr int kRaycastResultsIterations = 200;
6161
/// \brief Iterations for laser scan publication test
6262
static constexpr int kLaserScanIterations = 200;
6363
/// \brief Iteration threshold for sensor topic verification
@@ -194,6 +194,13 @@ TEST_F(CpuLidarTest,
194194

195195
bool resultsFound = false;
196196

197+
// Subscribe to the sensor topic so HasConnections() returns true
198+
// and the system requests raycasts from Physics.
199+
transport::Node node;
200+
std::function<void(const msgs::LaserScan &)> cb =
201+
[](const msgs::LaserScan &){};
202+
node.Subscribe("/test/cpu_lidar", cb);
203+
197204
test::Relay testSystem;
198205
testSystem.OnPostUpdate([&](const UpdateInfo &_info,
199206
const EntityComponentManager &_ecm)

0 commit comments

Comments
 (0)