Skip to content

Commit

Permalink
Adds plugins for sensor topic
Browse files Browse the repository at this point in the history
Signed-off-by: Voldivh <eloyabmfcv@gmail.com>
  • Loading branch information
Voldivh committed Aug 18, 2023
1 parent 4a8b23f commit d17a53d
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 3 deletions.
2 changes: 2 additions & 0 deletions python/test/joint_test.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="world_test">
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics" />
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque" />
<model name="model_test">

<link name="link_test_1">
Expand Down
7 changes: 4 additions & 3 deletions python/test/sensor_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,10 @@ def on_pre_udpate_cb(_info, _ecm):
# Pose Test
self.assertEqual(Pose3d(0, 1, 0, 0, 0, 0), sensor.pose(_ecm))
# Topic Test
# This is None because the entity does not have a
# components::SensorTopic component.
self.assertEqual(None, sensor.topic(_ecm))
if self.pre_iterations <= 1:
self.assertEqual(None, sensor.topic(_ecm))
else:
self.assertEqual('sensor_topic_test', sensor.topic(_ecm))
# Parent Test
self.assertEqual(j.entity(), sensor.parent(_ecm))

Expand Down

0 comments on commit d17a53d

Please sign in to comment.