Skip to content

Commit 55425a7

Browse files
author
henrykotze
committed
Test no z axis influence measurement
Signed-off-by: henrykotze <[email protected]>
1 parent 21432b2 commit 55425a7

File tree

1 file changed

+116
-0
lines changed

1 file changed

+116
-0
lines changed

test/integration/air_flow_system.cc

Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -345,3 +345,119 @@ TEST_F(AirFlowTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AirFlowMoveWindy))
345345
EXPECT_NEAR(10.04987562, msg.xy_speed(), 1e-3);
346346
EXPECT_NEAR(-0.0996686524911, msg.xy_direction(), 1e-2);
347347
}
348+
349+
/////////////////////////////////////////////////
350+
// The test checks that the sensor does not include airflow in its z-axis
351+
// in its measurement
352+
TEST_F(AirFlowTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AirFlowMoveZAxisWindy))
353+
{
354+
// Start server
355+
ServerConfig serverConfig;
356+
const auto sdfFile = gz::common::joinPaths(std::string(PROJECT_SOURCE_PATH),
357+
"test", "worlds", "air_flow_windy.sdf");
358+
serverConfig.SetSdfFile(sdfFile);
359+
360+
Server server(serverConfig);
361+
EXPECT_FALSE(server.Running());
362+
EXPECT_FALSE(*server.Running(0));
363+
364+
const std::string sensorName = "air_flow_sensor";
365+
366+
auto topic = "world/air_flow_sensor/model/air_flow_model/link/link/"
367+
"sensor/air_flow_sensor/air_flow";
368+
369+
bool updateChecked{false};
370+
371+
// Create a system that checks sensor topic
372+
TestFixture testSystem(serverConfig);
373+
374+
Link body;
375+
Model model;
376+
377+
378+
testSystem.OnConfigure(
379+
[&](const Entity &_worldEntity,
380+
const std::shared_ptr<const sdf::Element> &/*_sdf*/,
381+
EntityComponentManager &_ecm,
382+
EventManager &/*eventMgr*/)
383+
{
384+
World world(_worldEntity);
385+
auto modelEntity = world.ModelByName(_ecm, "air_flow_model");
386+
EXPECT_NE(modelEntity, kNullEntity);
387+
model = Model(modelEntity);
388+
389+
auto bodyEntity = model.LinkByName(_ecm, "link");
390+
EXPECT_NE(bodyEntity, kNullEntity);
391+
392+
body = Link(bodyEntity);
393+
body.EnableVelocityChecks(_ecm);
394+
395+
body.SetLinearVelocity(_ecm, gz::math::Vector3d(0, 0, -1));
396+
397+
}).OnPostUpdate([&](const UpdateInfo &_info,
398+
const EntityComponentManager &_ecm)
399+
{
400+
401+
_ecm.Each<components::AirFlowSensor, components::Name>(
402+
[&](const Entity &_entity,
403+
const components::AirFlowSensor *,
404+
const components::Name *_name) -> bool
405+
{
406+
EXPECT_EQ(_name->Data(), sensorName);
407+
408+
auto sensorComp = _ecm.Component<components::Sensor>(_entity);
409+
EXPECT_NE(nullptr, sensorComp);
410+
411+
if (_info.iterations == 1)
412+
return true;
413+
414+
// This component is created on the 2nd PreUpdate
415+
auto topicComp = _ecm.Component<components::SensorTopic>(_entity);
416+
EXPECT_NE(nullptr, topicComp);
417+
if (topicComp)
418+
{
419+
EXPECT_EQ(topic, topicComp->Data());
420+
}
421+
422+
updateChecked = true;
423+
424+
return true;
425+
});
426+
}).Finalize();
427+
428+
// Subscribe to air_flow topic
429+
bool received{false};
430+
msgs::AirFlowSensor msg;
431+
msg.Clear();
432+
std::function<void(const msgs::AirFlowSensor &)> cb =
433+
[&received, &msg](const msgs::AirFlowSensor &_msg)
434+
{
435+
436+
msg = _msg;
437+
received = true;
438+
};
439+
440+
transport::Node node;
441+
node.Subscribe(topic, cb);
442+
443+
444+
testSystem.Server()->Run(true, 10, false);
445+
// Run server
446+
// server.Run(true, 10, false);
447+
EXPECT_TRUE(updateChecked);
448+
449+
450+
// Wait for message to be received
451+
for (int sleep = 0; sleep < 30; ++sleep)
452+
{
453+
std::this_thread::sleep_for(std::chrono::milliseconds(100));
454+
}
455+
456+
EXPECT_TRUE(received);
457+
458+
// check air flow
459+
EXPECT_TRUE(msg.has_header());
460+
EXPECT_TRUE(msg.header().has_stamp());
461+
EXPECT_NEAR(5.0, msg.xy_speed(), 1e-3);
462+
EXPECT_NEAR(0.0, msg.xy_direction(), 1e-2);
463+
}

0 commit comments

Comments
 (0)