Skip to content

Commit

Permalink
Remove <gz:system_priority/> from test worlds (#2551)
Browse files Browse the repository at this point in the history
The system priority for the force-torque system was
explicitly set using XML tags in several test worlds
in #2494. These XML tags are no longer needed since #2500
was merged, so remove them now.

Also fix some outdated comments

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored Aug 27, 2024
1 parent 1184481 commit af7fabb
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 8 deletions.
4 changes: 1 addition & 3 deletions python/test/joint_test.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,7 @@
<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">
<gz:system_priority>10</gz:system_priority>
</plugin>
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque"/>
<model name="model_test">

<link name="link_test_1">
Expand Down
2 changes: 1 addition & 1 deletion src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -767,7 +767,7 @@ Physics::Physics() : System(), dataPtr(std::make_unique<PhysicsPrivate>())
//////////////////////////////////////////////////
System::PriorityType Physics::ConfigurePriority()
{
// Use constant from SystemPriorityConstants.hh
// Use constant from System.hh
return ::gz::sim::systems::kPhysicsPriority;
}

Expand Down
2 changes: 1 addition & 1 deletion src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -621,7 +621,7 @@ bool UserCommandsInterface::HasContactSensor(const Entity _collision)
//////////////////////////////////////////////////
System::PriorityType UserCommands::ConfigurePriority()
{
// Use constant from SystemPriorityConstants.hh
// Use constant from System.hh
return ::gz::sim::systems::kUserCommandsPriority;
}

Expand Down
4 changes: 1 addition & 3 deletions test/worlds/force_torque.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@
<real_time_factor>0</real_time_factor>
</physics>
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics" />
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque">
<gz:system_priority>10</gz:system_priority>
</plugin>
<plugin filename="gz-sim-forcetorque-system" name="gz::sim::systems::ForceTorque"/>
<plugin filename='gz-sim-scene-broadcaster-system' name='gz::sim::systems::SceneBroadcaster' />
<model name="ground_plane">
<static>true</static>
Expand Down

0 comments on commit af7fabb

Please sign in to comment.