Skip to content

Commit

Permalink
Minor test refactoring
Browse files Browse the repository at this point in the history
* Remove unused variable callbackCountRigidTerrain_
* Fix whitespace in model.sdf
* plowing_effect_test.world: set model pose instead
  of link pose, and raise spheres above ground level
  by setting initial Z coordinate to value of radius

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Jul 5, 2022
1 parent 4822d47 commit b6cf816
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 13 deletions.
6 changes: 0 additions & 6 deletions test/integration/plowing_effect.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ class PlowingEffectTricycle : public ServerFixture
private: physics::CollisionPtr wheelCollisionPtr_ = nullptr;
private: double plowingAngleRigidTerrain_;

private: int callbackCountRigidTerrain_ = 1;
private: const int maxCallbackCountRigidTerrain_ = 200;

/// constant params from SDF
Expand Down Expand Up @@ -77,11 +76,6 @@ class PlowingEffectSpheres : public ServerFixture
////////////////////////////////////////////////////////////////////////
void PlowingEffectTricycle::CallbackRigidTerrain(const ConstContactsPtr &_msg)
{
if(callbackCountRigidTerrain_ < maxCallbackCountRigidTerrain_)
{
callbackCountRigidTerrain_ = callbackCountRigidTerrain_ + 1;
}

std::string wheelCollisionStr = "original_tricycle::wheel_front::collision";
std::string groundCollisionStr = "plowing_effect_ground_plane::link::collision";

Expand Down
6 changes: 3 additions & 3 deletions test/models/plowing_effect_trisphere_cycle/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@
<ode>
<kp>4000</kp>
<kd>16</kd>
<max_vel>10</max_vel>
<max_vel>10</max_vel>
<min_depth>0.0005</min_depth>
</ode>
</contact>
Expand Down Expand Up @@ -328,7 +328,7 @@
<ode>
<kp>4000</kp>
<kd>16</kd>
<max_vel>10</max_vel>
<max_vel>10</max_vel>
<min_depth>0.0005</min_depth>
</ode>
</contact>
Expand Down Expand Up @@ -391,7 +391,7 @@
<ode>
<kp>4000</kp>
<kd>16</kd>
<max_vel>10</max_vel>
<max_vel>10</max_vel>
<min_depth>0.0005</min_depth>
</ode>
</contact>
Expand Down
8 changes: 4 additions & 4 deletions test/worlds/plowing_effect_test.world
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
</include>

<model name="sphere1">
<pose>0 0 0.4 0 0 0</pose>
<link name='base_link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>5.0</mass>
<inertia>
Expand Down Expand Up @@ -47,8 +47,8 @@
</model>

<model name= "sphere2" xmlns:gz="https://gazebosim.org/schema">
<pose>0 1 0.4 0 0 0</pose>
<link name="base_link">
<pose>0 1 0 0 0 0</pose>
<inertial>
<mass>5.0</mass>
<inertia>
Expand Down Expand Up @@ -96,8 +96,8 @@
</model>

<model name= "sphere3" xmlns:gz="https://gazebosim.org/schema">
<pose>0 2 0.4 0 0 0</pose>
<link name="base_link">
<pose>0 2 0 0 0 0</pose>
<inertial>
<mass>5.0</mass>
<inertia>
Expand Down Expand Up @@ -145,8 +145,8 @@
</model>

<model name= "sphere4" xmlns:gz="https://gazebosim.org/schema">
<pose>0 3 0.4 0 0 0</pose>
<link name="base_link">
<pose>0 3 0 0 0 0</pose>
<inertial>
<mass>5.0</mass>
<inertia>
Expand Down

0 comments on commit b6cf816

Please sign in to comment.