Skip to content

Commit

Permalink
Clarify how sim time is interpreted in a System's step (#401)
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
  • Loading branch information
adlarkin committed Dec 2, 2020
1 parent 327cde7 commit 770b1e7
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 12 deletions.
27 changes: 19 additions & 8 deletions include/ignition/gazebo/System.hh
Original file line number Diff line number Diff line change
Expand Up @@ -44,21 +44,32 @@ namespace ignition
/// will only operate on an Entity if it has all of the required
/// Components.
///
/// Systems are executed in three phases:
/// Systems are executed in three phases, with each phase for a given step
/// corresponding to the entities at time UpdateInfo::simTime:
/// * PreUpdate
/// * Has read-write access to world entities and components
/// * Executed with simulation time at (t0)
/// * Has read-write access to world entities and components.
/// * This is where systems say what they'd like to happen at time
/// UpdateInfo::simTime.
/// * Can be used to modify state before physics runs, for example for
/// applying control signals or performing network syncronization.
/// * Update
/// * Has read-write access to world entities and components
/// * Responsible for propagating time from (t0) to (t0 + dt)
/// * Used for physics simulation step
/// * Has read-write access to world entities and components.
/// * Used for physics simulation step (i.e., simulates what happens at
/// time UpdateInfo::simTime).
/// * PostUpdate
/// * Has read-only access to world entities and components
/// * Executed with simulation time at (t0 + dt)
/// * Has read-only access to world entities and components.
/// * Captures everything that happened at time UpdateInfo::simTime.
/// * Used to read out results at the end of a simulation step to be used
/// for sensor or controller updates.
///
/// It's important to note that UpdateInfo::simTime does not refer to the
/// current time, but the time reached after the PreUpdate and Update calls
/// have finished. So, if any of the *Update functions are called with
/// simulation paused, time does not advance, which means the time reached
/// after PreUpdate and Update is the same as the starting time. This
/// explains why UpdateInfo::simTime is initially 0 if simulation is started
/// paused, while UpdateInfo::simTime is initially UpdateInfo::dt if
/// simulation is started un-paused.
class IGNITION_GAZEBO_VISIBLE System
{
/// \brief Constructor
Expand Down
11 changes: 7 additions & 4 deletions tutorials/create_system_plugins.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,20 @@ there are currently three additional available interfaces:

1. ISystemPreUpdate
1. Has read-write access to world entities and components.
2. Executed with simulation time at (t0).
2. This is where systems say what they'd like to happen at time ignition::gazebo::UpdateInfo::simTime.
3. Can be used to modify state before physics runs, for example for applying control signals or performing network synchronization.
2. ISystemUpdate
1. Has read-write access to world entities and components.
2. Responsible for propagating time from (t0) to (t0 + dt).
3. Used for physics simulation step.
2. Used for physics simulation step (i.e., simulates what happens at time ignition::gazebo::UpdateInfo::simTime).
3. ISystemPostUpdate
1. Has read-only access to world entities and components.
2. Executed with simulation time at (t0 + dt).
2. Captures everything that happened at time ignition::gazebo::UpdateInfo::simTime.
3. Used to read out results at the end of a simulation step to be used for sensor or controller updates.

It's important to note that ignition::gazebo::UpdateInfo::simTime does not refer to the current time, but the time reached after the `PreUpdate` and `Update` calls have finished.
So, if any of the `*Update` functions are called with simulation paused, time does not advance, which means the time reached after `PreUpdate` and `Update` is the same as the starting time.
This explains why ignition::gazebo::UpdateInfo::simTime is initially 0 if simulation is started paused, while ignition::gazebo::UpdateInfo::simTime is initially ignition::gazebo::UpdateInfo::dt if simulation is started un-paused.

Systems that are only used to read the current state of the world (sensors,
graphics, and rendering) should implement `ISystemPostUpdate`.

Expand Down

0 comments on commit 770b1e7

Please sign in to comment.