Skip to content

Commit

Permalink
Modifies the name of the constant in test files
Browse files Browse the repository at this point in the history
Signed-off-by: Voldivh <[email protected]>
  • Loading branch information
Voldivh committed Aug 11, 2023
1 parent 21380ea commit 5f0a2bf
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 11 deletions.
12 changes: 6 additions & 6 deletions python/test/model_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import unittest

from gz.common import set_verbosity
from gz_test_deps.sim import k_null_entity, TestFixture, Model, World, world_entity
from gz_test_deps.sim import K_NULL_ENTITY, TestFixture, Model, World, world_entity

class TestModel(unittest.TestCase):
post_iterations = 0
Expand All @@ -36,11 +36,11 @@ def on_post_udpate_cb(_info, _ecm):
def on_pre_udpate_cb(_info, _ecm):
self.pre_iterations += 1
world_e = world_entity(_ecm)
self.assertNotEqual(k_null_entity, world_e)
self.assertNotEqual(K_NULL_ENTITY, world_e)
w = World(world_e)
model = Model(w.model_by_name(_ecm, 'model_test'))
# Entity Test
self.assertNotEqual(k_null_entity, model.entity())
self.assertNotEqual(K_NULL_ENTITY, model.entity())
# Valid Test
self.assertTrue(model.valid(_ecm))
# Name Test
Expand All @@ -52,11 +52,11 @@ def on_pre_udpate_cb(_info, _ecm):
# Wind Mode Test
self.assertTrue(model.wind_mode(_ecm))
# Get Joints Test
self.assertNotEqual(k_null_entity, model.joint_by_name(_ecm, 'model_joint_test'))
self.assertNotEqual(K_NULL_ENTITY, model.joint_by_name(_ecm, 'model_joint_test'))
self.assertEqual(1, model.joint_count(_ecm))
# Get Links Test
self.assertNotEqual(k_null_entity, model.link_by_name(_ecm, 'model_link_test_1'))
self.assertNotEqual(k_null_entity, model.link_by_name(_ecm, 'model_link_test_2'))
self.assertNotEqual(K_NULL_ENTITY, model.link_by_name(_ecm, 'model_link_test_1'))
self.assertNotEqual(K_NULL_ENTITY, model.link_by_name(_ecm, 'model_link_test_2'))
self.assertEqual(2, model.link_count(_ecm))

def on_udpate_cb(_info, _ecm):
Expand Down
10 changes: 5 additions & 5 deletions python/test/world_TEST.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import unittest

from gz.common import set_verbosity
from gz_test_deps.sim import k_null_entity, TestFixture, World, world_entity
from gz_test_deps.sim import K_NULL_ENTITY, TestFixture, World, world_entity
from gz_test_deps.math import SphericalCoordinates, Vector3d
from gz_test_deps.sdformat import Atmosphere

Expand All @@ -38,7 +38,7 @@ def on_post_udpate_cb(_info, _ecm):
def on_pre_udpate_cb(_info, _ecm):
self.pre_iterations += 1
world_e = world_entity(_ecm)
self.assertNotEqual(k_null_entity, world_e)
self.assertNotEqual(K_NULL_ENTITY, world_e)
world = World(world_e)
# Valid Test
self.assertTrue(world.valid(_ecm))
Expand Down Expand Up @@ -67,13 +67,13 @@ def on_pre_udpate_cb(_info, _ecm):
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).elevation_reference())
self.assertAlmostEqual(float(0), world.spherical_coordinates(_ecm).heading_offset().degree())
# Light Test
self.assertNotEqual(k_null_entity, world.light_by_name(_ecm, 'light_point_test'))
self.assertNotEqual(K_NULL_ENTITY, world.light_by_name(_ecm, 'light_point_test'))
self.assertEqual(1, world.light_count(_ecm))
# Actor test
self.assertNotEqual(k_null_entity, world.actor_by_name(_ecm, 'actor_test'))
self.assertNotEqual(K_NULL_ENTITY, world.actor_by_name(_ecm, 'actor_test'))
self.assertEqual(1, world.actor_count(_ecm))
# Model Test
self.assertNotEqual(k_null_entity, world.model_by_name(_ecm, 'model_test'))
self.assertNotEqual(K_NULL_ENTITY, world.model_by_name(_ecm, 'model_test'))
self.assertEqual(1, world.model_count(_ecm))

def on_udpate_cb(_info, _ecm):
Expand Down

0 comments on commit 5f0a2bf

Please sign in to comment.