Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support spawning during log playback #346

Merged
merged 4 commits into from
Sep 11, 2020
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions include/ignition/gazebo/EntityComponentManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -696,6 +696,12 @@ namespace ignition
const Entity _entity, const ComponentTypeId _type,
gazebo::ComponentState _c = ComponentState::OneTimeChange);

/// \brief All future entities will have an id that starts at _offset.
/// This can be used to avoid entity id collisions, such as during log
/// playback.
/// \param[in] _offset Offset value.
public: void SetEntityCreateOffset(uint64_t _offset);
chapulina marked this conversation as resolved.
Show resolved Hide resolved

/// \brief Mark all components as not changed.
protected: void SetAllComponentsUnchanged();

Expand Down
6 changes: 6 additions & 0 deletions src/EntityComponentManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1224,3 +1224,9 @@ std::unordered_set<ComponentTypeId> EntityComponentManager::ComponentTypes(

return result;
}

/////////////////////////////////////////////////
void EntityComponentManager::SetEntityCreateOffset(uint64_t _offset)
{
this->dataPtr->entityCount = _offset;
chapulina marked this conversation as resolved.
Show resolved Hide resolved
}
11 changes: 7 additions & 4 deletions src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,17 +68,20 @@ struct DefaultWorld
std::string("<plugin filename='libignition-gazebo") +
IGNITION_GAZEBO_MAJOR_VERSION_STR + "-scene-broadcaster-system.so' "
"name='ignition::gazebo::systems::SceneBroadcaster'></plugin>"
}};
},
{
std::string("<plugin filename='libignition-gazebo") +
IGNITION_GAZEBO_MAJOR_VERSION_STR + "-user-commands-system.so' " +
"name='ignition::gazebo::systems::UserCommands'></plugin>"
}
};

// The set of default gazebo plugins.
if (_config.LogPlaybackPath().empty())
{
pluginsV.push_back(std::string("<plugin filename='libignition-gazebo") +
IGNITION_GAZEBO_MAJOR_VERSION_STR + "-physics-system.so' "
"name='ignition::gazebo::systems::Physics'></plugin>");
pluginsV.push_back(std::string("<plugin filename='libignition-gazebo") +
IGNITION_GAZEBO_MAJOR_VERSION_STR + "-user-commands-system.so' " +
"name='ignition::gazebo::systems::UserCommands'></plugin>");
}

// Playback plugin
Expand Down
4 changes: 4 additions & 0 deletions src/systems/log/LogPlayback.cc
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,10 @@ void LogPlayback::Configure(const Entity &,
// Prepend working directory if path is relative
this->dataPtr->logPath = common::absPath(this->dataPtr->logPath);

// Set the entity offset.
// \todo This number should be included in the log file.
_ecm.SetEntityOffset(90000);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How about ticketing an issue for keeping track of the max entity count during log record?

Also, maybe a number like std::numeric_limits<int64_t>::max() / 2 could be more generic than the current number.

Copy link
Contributor Author

@nkoenig nkoenig Sep 11, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The issue is #347.

Changed offset to use half of the max value in 8a2b44c


// If path is a file, assume it is a compressed file
// (Otherwise assume it is a directory containing recorded files.)
if (common::isFile(this->dataPtr->logPath))
Expand Down