Skip to content

Commit

Permalink
Merge branch 'master' into any_geom_buoyant
Browse files Browse the repository at this point in the history
  • Loading branch information
caguero authored Aug 3, 2022
2 parents 43b83ea + 5592bcb commit 12845d2
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 25 deletions.
9 changes: 0 additions & 9 deletions vrx_gazebo/include/vrx_gazebo/perception_scoring_plugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -103,10 +103,6 @@ class PerceptionObject
/// <name> Landmark name.
/// <pose> Initial object pose.
///
/// <loop_forever>: Optional parameter. If true, all objects will be spawned
/// as a circular buffer. After spawning the last element of the collection,
/// the first one will be inserted.
///
/// <frame>: Optional parameter. If present, the poses of the objects will be
/// in the frame of this link/model. Otherwise the world frame is used.
///
Expand All @@ -130,7 +126,6 @@ class PerceptionObject
/// <running_state_duration>300</running_state_duration>
///
/// <!-- Parameters for PopulationPlugin -->
/// <loop_forever>false</loop_forever>
/// <frame>wamv</frame>
/// <object_sequence>
/// <object>
Expand Down Expand Up @@ -203,10 +198,6 @@ class PerceptionScoringPlugin : public ScoringPlugin
/// \brief The time specified in the object is relative to this time.
public: gazebo::common::Time startTime;

/// \brief When true, "objects" will be repopulated when the object queue
/// is empty, creating an infinite supply of objects.
public: bool loopForever = false;

/// \brief Link/model name for the object poses use as their frame of
/// reference
public: std::string frameName = std::string();
Expand Down
16 changes: 1 addition & 15 deletions vrx_gazebo/src/perception_scoring_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -167,11 +167,6 @@ void PerceptionScoringPlugin::Load(gazebo::physics::WorldPtr _world,
this->world = _world;
this->sdf = _sdf;

if (_sdf->HasElement("loop_forever"))
{
sdf::ElementPtr loopElem = _sdf->GetElement("loop_forever");
this->loopForever = loopElem->Get<bool>();
}

if (_sdf->HasElement("frame"))
{
Expand Down Expand Up @@ -364,16 +359,7 @@ void PerceptionScoringPlugin::OnUpdate()
this->SetScore(this->Score() / this->objects.size());
ROS_INFO_NAMED("Perception run score: ", "%f", this->Score());

// if loop, restart
if (this->loopForever)
{
this->objectsDespawned = 0;
this->Restart();
}
else
{
this->Finish();
}
this->Finish();
}
}

Expand Down
1 change: 0 additions & 1 deletion vrx_gazebo/worlds/perception_task.world.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
<ready_state_duration>10.0</ready_state_duration>
<running_state_duration>300</running_state_duration>
<!-- Parameters for PopulationPlugin -->
<loop_forever>true</loop_forever>
<frame>wamv</frame>
<!-- Pose of each object is expressed relative to the body frame
of the object named in the frame field - i.e., relative to
Expand Down

0 comments on commit 12845d2

Please sign in to comment.