diff --git a/framework/doc/content/syntax/ICs/index.md b/framework/doc/content/syntax/ICs/index.md
index 55369db83167..03c34320a151 100644
--- a/framework/doc/content/syntax/ICs/index.md
+++ b/framework/doc/content/syntax/ICs/index.md
@@ -62,6 +62,13 @@ object's variable *must* be defined on the block - otherwise the IC for the
 next lowest block ID for the node is used - and so forth until one has the
 variable defined.
 
+## Old and Older ICs
+
+The ICs system supports the ability to set ICs on old and older states. This can be useful for initializing old and older states of variables needed for various time integration schemes. It can be set with the [!param](/ICs/ConstantIC/state) parameter and specifying `OLD` or `OLDER`.
+
+
+
+
 !syntax list /ICs objects=True actions=False subsystems=False
 
 !syntax list /ICs objects=False actions=False subsystems=True
diff --git a/framework/include/auxkernels/CopyValueAux.h b/framework/include/auxkernels/CopyValueAux.h
index 70b34884739e..bff71f668afe 100644
--- a/framework/include/auxkernels/CopyValueAux.h
+++ b/framework/include/auxkernels/CopyValueAux.h
@@ -24,6 +24,9 @@ class CopyValueAux : public AuxKernel
 protected:
   virtual Real computeValue() override;
 
+  // variable used to specify state being copied
+  unsigned short _state;
+
   /// The variable to project from
   const VariableValue & _v;
 
diff --git a/framework/include/fvics/FVInitialConditionBase.h b/framework/include/fvics/FVInitialConditionBase.h
index b5494e26c88e..fe2068c5e06d 100644
--- a/framework/include/fvics/FVInitialConditionBase.h
+++ b/framework/include/fvics/FVInitialConditionBase.h
@@ -9,6 +9,7 @@
 
 #pragma once
 
+#include "InitialConditionInterface.h"
 #include "MooseObject.h"
 #include "FunctionInterface.h"
 #include "UserObjectInterface.h"
@@ -30,6 +31,7 @@ class Point;
  * description
  */
 class FVInitialConditionBase : public MooseObject,
+                               public InitialConditionInterface,
                                public BlockRestrictable,
                                public FunctionInterface,
                                public Restartable,
diff --git a/framework/include/ics/InitialConditionBase.h b/framework/include/ics/InitialConditionBase.h
index fce7350b6779..d7238e325842 100644
--- a/framework/include/ics/InitialConditionBase.h
+++ b/framework/include/ics/InitialConditionBase.h
@@ -9,6 +9,7 @@
 
 #pragma once
 
+#include "InitialConditionInterface.h"
 #include "MooseObject.h"
 #include "Coupleable.h"
 #include "FunctionInterface.h"
@@ -36,6 +37,7 @@ class Point;
  * hierarchy: the `compute` method
  */
 class InitialConditionBase : public MooseObject,
+                             public InitialConditionInterface,
                              public BlockRestrictable,
                              public Coupleable,
                              public MaterialPropertyInterface,
diff --git a/framework/include/ics/InitialConditionInterface.h b/framework/include/ics/InitialConditionInterface.h
new file mode 100644
index 000000000000..5ad8ec2df900
--- /dev/null
+++ b/framework/include/ics/InitialConditionInterface.h
@@ -0,0 +1,41 @@
+//* This file is part of the MOOSE framework
+//* https://www.mooseframework.org
+//*
+//* All rights reserved, see COPYRIGHT for full restrictions
+//* https://github.com/idaholab/moose/blob/master/COPYRIGHT
+//*
+//* Licensed under LGPL 2.1, please see LICENSE for details
+//* https://www.gnu.org/licenses/lgpl-2.1.html
+
+#pragma once
+
+#include "InputParameters.h"
+
+/**
+ * InitialConditionInterface serves as the abstract class for InitialConditions,
+ * FVInitialConditions, and ScalarInitialConditions
+ */
+class InitialConditionInterface
+{
+public:
+  /**
+   * Constructor
+   *
+   * @param parameters The parameters object holding data for the class to use.
+   */
+  InitialConditionInterface(const InputParameters & parameters);
+
+  virtual ~InitialConditionInterface();
+
+  static InputParameters validParams();
+
+  /**
+   * Retrieves the state of this initial condition.
+   * @return The state of this initial condition.
+   */
+  unsigned short getState() const;
+
+protected:
+  // variable used when applying initial conditions to previous states
+  unsigned short _my_state;
+};
diff --git a/framework/include/ics/InitialConditionWarehouse.h b/framework/include/ics/InitialConditionWarehouse.h
index 58149111cb64..e0524451f524 100644
--- a/framework/include/ics/InitialConditionWarehouse.h
+++ b/framework/include/ics/InitialConditionWarehouse.h
@@ -40,8 +40,13 @@ class InitialConditionWarehouse : public MooseObjectWarehouseBase<InitialConditi
 
 protected:
   ///@{
-  /// Variable name to block/boundary IDs for error checking
-  std::vector<std::map<std::string, std::set<BoundaryID>>> _boundary_ics;
-  std::vector<std::map<std::string, std::set<SubdomainID>>> _block_ics;
+  /// Maps used to check if multiple ICs define the same variable on the same block/boundary for the same state (e.g CURRENT, OLD, OLDER).
+  /// They are vectors of maps because each map is repeated for each thread.
+  /// Each map relates string-int tuples to a set of block/boundary IDs.
+  /// The string-int tuple is a unique identifier for a specific variable and state. The string-int tuple is renamed to ic_key_type for clarity.
+  /// The algorithm then makes sure that a new IC object does not overlap with a previous IC object (i.e. same block/boundary).
+  using ic_key_type = std::tuple<VariableName, unsigned short>;
+  std::vector<std::map<ic_key_type, std::set<BoundaryID>>> _boundary_ics;
+  std::vector<std::map<ic_key_type, std::set<SubdomainID>>> _block_ics;
   ///@}
 };
diff --git a/framework/include/ics/ScalarInitialCondition.h b/framework/include/ics/ScalarInitialCondition.h
index d25e5c245b37..d90587d8c31b 100644
--- a/framework/include/ics/ScalarInitialCondition.h
+++ b/framework/include/ics/ScalarInitialCondition.h
@@ -9,6 +9,7 @@
 
 #pragma once
 
+#include "InitialConditionInterface.h"
 #include "MooseObject.h"
 #include "ScalarCoupleable.h"
 #include "FunctionInterface.h"
@@ -30,6 +31,7 @@ class DenseVector;
  * InitialConditions are objects that set the initial value of variables.
  */
 class ScalarInitialCondition : public MooseObject,
+                               public InitialConditionInterface,
                                public ScalarCoupleable,
                                public FunctionInterface,
                                public UserObjectInterface,
diff --git a/framework/include/problems/FEProblemBase.h b/framework/include/problems/FEProblemBase.h
index 334be7ff6787..9aeef329f1ad 100644
--- a/framework/include/problems/FEProblemBase.h
+++ b/framework/include/problems/FEProblemBase.h
@@ -866,6 +866,12 @@ class FEProblemBase : public SubProblem, public Restartable
 
   void projectSolution();
 
+  /**
+   *  Retrieves the current initial condition state.
+   * @return  current initial condition state
+   */
+  unsigned short getCurrentICState();
+
   /**
    * Project initial conditions for custom \p elem_range and \p bnd_node_range
    * This is needed when elements/boundary nodes are added to a specific subdomain
@@ -2790,6 +2796,9 @@ class FEProblemBase : public SubProblem, public Restartable
   /// requested an AD material property or whether any suppier has declared an AD material property
   bool _using_ad_mat_props;
 
+  // loop state during projection of initial conditions
+  unsigned short _current_ic_state;
+
 private:
   /**
    * Handle exceptions. Note that the result of this call will be a thrown MooseException. The
diff --git a/framework/src/auxkernels/CopyValueAux.C b/framework/src/auxkernels/CopyValueAux.C
index bed60a4c2b0f..94889a1fceca 100644
--- a/framework/src/auxkernels/CopyValueAux.C
+++ b/framework/src/auxkernels/CopyValueAux.C
@@ -19,11 +19,22 @@ CopyValueAux::validParams()
   params.addClassDescription("Returns the specified variable as an auxiliary variable with a "
                              "simple copy of the variable values.");
   params.addRequiredCoupledVar("source", "Variable to take the value of.");
+  MooseEnum stateEnum("CURRENT=0 OLD=1 OLDER=2", "CURRENT");
+  params.addParam<MooseEnum>(
+      "state",
+      stateEnum,
+      "This parameter specifies the state being copied. CURRENT=0 OLD=1 OLDER=2. Copying an older "
+      "state allows access to previous solution information if necessary.");
   return params;
 }
 
 CopyValueAux::CopyValueAux(const InputParameters & parameters)
-  : AuxKernel(parameters), _v(coupledValue("source")), _source_variable(*getVar("source", 0))
+  : AuxKernel(parameters),
+    _state(getParam<MooseEnum>("state")),
+    _v(_state == 0   ? coupledValue("source")
+       : _state == 1 ? coupledValueOld("source")
+                     : coupledValueOlder("source")),
+    _source_variable(*getVar("source", 0))
 {
   if (_var.feType().family != _source_variable.feType().family)
     paramError("variable",
diff --git a/framework/src/fvics/FVInitialConditionBase.C b/framework/src/fvics/FVInitialConditionBase.C
index 9a35d33601a0..07949cd7f530 100644
--- a/framework/src/fvics/FVInitialConditionBase.C
+++ b/framework/src/fvics/FVInitialConditionBase.C
@@ -16,6 +16,7 @@ InputParameters
 FVInitialConditionBase::validParams()
 {
   InputParameters params = MooseObject::validParams();
+  params += InitialConditionInterface::validParams();
   params += BlockRestrictable::validParams();
 
   params.addRequiredParam<VariableName>("variable",
@@ -28,6 +29,7 @@ FVInitialConditionBase::validParams()
 
 FVInitialConditionBase::FVInitialConditionBase(const InputParameters & parameters)
   : MooseObject(parameters),
+    InitialConditionInterface(parameters),
     BlockRestrictable(this),
     FunctionInterface(this),
     Restartable(this, "FVInitialConditionBases"),
diff --git a/framework/src/ics/InitialConditionBase.C b/framework/src/ics/InitialConditionBase.C
index acd1c1e547c2..1d4c668ea71c 100644
--- a/framework/src/ics/InitialConditionBase.C
+++ b/framework/src/ics/InitialConditionBase.C
@@ -16,6 +16,7 @@ InputParameters
 InitialConditionBase::validParams()
 {
   InputParameters params = MooseObject::validParams();
+  params += InitialConditionInterface::validParams();
   params += BlockRestrictable::validParams();
   params += BoundaryRestrictable::validParams();
   params += MaterialPropertyInterface::validParams();
@@ -38,6 +39,7 @@ InitialConditionBase::validParams()
 
 InitialConditionBase::InitialConditionBase(const InputParameters & parameters)
   : MooseObject(parameters),
+    InitialConditionInterface(parameters),
     BlockRestrictable(this),
     Coupleable(this,
                getParam<SystemBase *>("_sys")
diff --git a/framework/src/ics/InitialConditionInterface.C b/framework/src/ics/InitialConditionInterface.C
new file mode 100644
index 000000000000..6fcf00982521
--- /dev/null
+++ b/framework/src/ics/InitialConditionInterface.C
@@ -0,0 +1,45 @@
+//* This file is part of the MOOSE framework
+//* https://www.mooseframework.org
+//*
+//* All rights reserved, see COPYRIGHT for full restrictions
+//* https://github.com/idaholab/moose/blob/master/COPYRIGHT
+//*
+//* Licensed under LGPL 2.1, please see LICENSE for details
+//* https://www.gnu.org/licenses/lgpl-2.1.html
+
+#include "InitialConditionInterface.h"
+#include "InputParameters.h"
+#include "MooseEnum.h"
+
+InputParameters
+InitialConditionInterface::validParams()
+{
+  InputParameters params = emptyInputParameters();
+
+  MooseEnum stateEnum("CURRENT=0 OLD=1 OLDER=2", "CURRENT");
+  params.addParam<MooseEnum>(
+      "state",
+      stateEnum,
+      "This parameter is used to set old state solutions at the start of simulation. If specifying "
+      "multiple states at the start of simulation, use one IC object for each state being "
+      "specified. The states are CURRENT=0 OLD=1 OLDER=2. States older than 2 are not currently "
+      "supported. When the user only specifies current state, the solution is copied to the old "
+      "and older states, as expected. This functionality is mainly used for dynamic simulations "
+      "with explicit time integration schemes, where old solution states are used in the velocity "
+      "and acceleration approximations.");
+
+  return params;
+}
+
+InitialConditionInterface::InitialConditionInterface(const InputParameters & parameters)
+  : _my_state(parameters.get<MooseEnum>("state"))
+{
+}
+
+InitialConditionInterface::~InitialConditionInterface() {}
+
+unsigned short
+InitialConditionInterface::getState() const
+{
+  return _my_state;
+}
diff --git a/framework/src/ics/InitialConditionWarehouse.C b/framework/src/ics/InitialConditionWarehouse.C
index 842dff6de154..8d554ca34c22 100644
--- a/framework/src/ics/InitialConditionWarehouse.C
+++ b/framework/src/ics/InitialConditionWarehouse.C
@@ -35,6 +35,7 @@ InitialConditionWarehouse::addObject(std::shared_ptr<InitialConditionBase> objec
 {
   // Check that when object is boundary restricted that the variable is nodal
   const MooseVariableFEBase & var = object->variable();
+  const auto ic_key = std::tuple(var.name(), object->getState());
 
   // Boundary Restricted
   if (object->boundaryRestricted())
@@ -43,43 +44,42 @@ InitialConditionWarehouse::addObject(std::shared_ptr<InitialConditionBase> objec
       mooseError("You are trying to set a boundary restricted variable on non-nodal variable. That "
                  "is not allowed.");
 
-    std::map<std::string, std::set<BoundaryID>>::const_iterator iter =
-        _boundary_ics[tid].find(var.name());
+    const auto iter = _boundary_ics[tid].find(ic_key);
     if (iter != _boundary_ics[tid].end() && object->hasBoundary(iter->second))
       mooseError("The initial condition '",
                  object->name(),
-                 "' is being defined on a boundary that already has an initial condition defined.");
+                 "' is being defined on a boundary that already has an initial condition defined "
+                 "with the same variable and state.");
     else
-      _boundary_ics[tid][var.name()].insert(object->boundaryIDs().begin(),
-                                            object->boundaryIDs().end());
+      _boundary_ics[tid][ic_key].insert(object->boundaryIDs().begin(), object->boundaryIDs().end());
   }
 
   // Block Restricted
   else if (object->blockRestricted())
   {
-    std::map<std::string, std::set<SubdomainID>>::const_iterator iter =
-        _block_ics[tid].find(var.name());
+    auto iter = _block_ics[tid].find(ic_key);
     if (iter != _block_ics[tid].end() &&
         (object->hasBlocks(iter->second) ||
          (iter->second.find(Moose::ANY_BLOCK_ID) != iter->second.end())))
       mooseError("The initial condition '",
                  object->name(),
-                 "' is being defined on a block that already has an initial condition defined.");
+                 "' is being defined on a block that already has an initial condition defined "
+                 "with the same variable and state.");
     else
-      _block_ics[tid][var.name()].insert(object->blockIDs().begin(), object->blockIDs().end());
+      _block_ics[tid][ic_key].insert(object->blockIDs().begin(), object->blockIDs().end());
   }
 
   // Non-restricted
   else
   {
-    std::map<std::string, std::set<SubdomainID>>::const_iterator iter =
-        _block_ics[tid].find(var.name());
+    auto iter = _block_ics[tid].find(ic_key);
     if (iter != _block_ics[tid].end())
       mooseError("The initial condition '",
                  object->name(),
-                 "' is being defined on a block that already has an initial condition defined.");
+                 "' is being defined on a block that already has an initial condition defined "
+                 "with the same variable and state.");
     else
-      _block_ics[tid][var.name()].insert(Moose::ANY_BLOCK_ID);
+      _block_ics[tid][ic_key].insert(Moose::ANY_BLOCK_ID);
   }
 
   // Add the IC to the storage
diff --git a/framework/src/ics/ScalarInitialCondition.C b/framework/src/ics/ScalarInitialCondition.C
index 929c6bfc277c..8b766d09dadf 100644
--- a/framework/src/ics/ScalarInitialCondition.C
+++ b/framework/src/ics/ScalarInitialCondition.C
@@ -16,6 +16,7 @@ InputParameters
 ScalarInitialCondition::validParams()
 {
   InputParameters params = MooseObject::validParams();
+  params += InitialConditionInterface::validParams();
   params.addParam<VariableName>(
       "variable", "The variable this initial condition is supposed to provide values for.");
 
@@ -26,6 +27,7 @@ ScalarInitialCondition::validParams()
 
 ScalarInitialCondition::ScalarInitialCondition(const InputParameters & parameters)
   : MooseObject(parameters),
+    InitialConditionInterface(parameters),
     ScalarCoupleable(this),
     FunctionInterface(this),
     UserObjectInterface(this),
diff --git a/framework/src/loops/ComputeInitialConditionThread.C b/framework/src/loops/ComputeInitialConditionThread.C
index c87ac8210280..6b0f813a8042 100644
--- a/framework/src/loops/ComputeInitialConditionThread.C
+++ b/framework/src/loops/ComputeInitialConditionThread.C
@@ -29,6 +29,7 @@ ComputeInitialConditionThread::operator()(const ConstElemRange & range)
 {
   ParallelUniqueId puid;
   _tid = puid.id;
+  const auto current_ic_state = _fe_problem.getCurrentICState();
 
   const InitialConditionWarehouse & warehouse = _fe_problem.getInitialConditionWarehouse();
   printGeneralExecutionInformation();
@@ -65,7 +66,8 @@ ComputeInitialConditionThread::operator()(const ConstElemRange & range)
       if (warehouse.hasActiveBlockObjects(id, _tid))
         for (auto ic : warehouse.getActiveBlockObjects(id, _tid))
         {
-          if ((id != elem->subdomain_id()) && !ic->variable().isNodal())
+          if ((id != elem->subdomain_id() && !ic->variable().isNodal()) ||
+              ic->getState() != current_ic_state)
             continue;
           order.push_back(&(ic->variable()));
           groups[&(ic->variable())].push_back(ic);
diff --git a/framework/src/problems/FEProblemBase.C b/framework/src/problems/FEProblemBase.C
index c17669d50aac..7382d4009fe8 100644
--- a/framework/src/problems/FEProblemBase.C
+++ b/framework/src/problems/FEProblemBase.C
@@ -470,6 +470,7 @@ FEProblemBase::FEProblemBase(const InputParameters & parameters)
     _is_petsc_options_inserted(false),
     _line_search(nullptr),
     _using_ad_mat_props(false),
+    _current_ic_state(0),
     _error_on_jacobian_nonzero_reallocation(
         isParamValid("error_on_jacobian_nonzero_reallocation")
             ? getParam<bool>("error_on_jacobian_nonzero_reallocation")
@@ -1133,6 +1134,59 @@ FEProblemBase::initialSetup()
   {
     // During initial setup the solution is copied to the older solution states (old, older, etc)
     copySolutionsBackwards();
+
+    // Check if there are old state initial conditions
+    auto ics = _ics.getActiveObjects();
+    auto fv_ics = _fv_ics.getActiveObjects();
+    auto scalar_ics = _scalar_ics.getActiveObjects();
+    unsigned short ic_state_max = 0;
+
+    auto findMax = [&ic_state_max](const auto & obj_list)
+    {
+      for (auto ic : obj_list.getActiveObjects())
+        ic_state_max = std::max(ic_state_max, ic->getState());
+    };
+    findMax(_ics);
+    findMax(_fv_ics);
+    findMax(_scalar_ics);
+
+    // if there are old state ICs, compute them and write to old states accordingly
+    if (ic_state_max > 0)
+    {
+      // state 0 copy (we'll overwrite current state when evaluating ICs and need to restore it once
+      // we're done with the old/older state ICs)
+      std::vector<std::unique_ptr<NumericVector<Real>>> state0_sys_buffers(_solver_systems.size());
+      std::unique_ptr<NumericVector<Real>> state0_aux_buffer;
+
+      // save state 0
+      for (const auto i : index_range(_solver_systems))
+        state0_sys_buffers[i] = _solver_systems[i]->solutionState(0).clone();
+
+      state0_aux_buffer = _aux->solutionState(0).clone();
+
+      // compute old state ICs
+      for (_current_ic_state = 1; _current_ic_state <= ic_state_max; _current_ic_state++)
+      {
+        projectSolution();
+
+        for (auto & sys : _solver_systems)
+          sys->solutionState(_current_ic_state) = sys->solutionState(0);
+
+        _aux->solutionState(_current_ic_state) = _aux->solutionState(0);
+      }
+      _current_ic_state = 0;
+
+      // recover state 0
+      for (const auto i : index_range(_solver_systems))
+      {
+        _solver_systems[i]->solutionState(0) = *state0_sys_buffers[i];
+        _solver_systems[i]->solutionState(0).close();
+        _solver_systems[i]->update();
+      }
+      _aux->solutionState(0) = *state0_aux_buffer;
+      _aux->solutionState(0).close();
+      _aux->update();
+    }
   }
 
   if (!_app.isRecovering())
@@ -9068,3 +9122,9 @@ FEProblemBase::setCurrentAlgebraicBndNodeRange(ConstBndNodeRange * range)
 
   _current_algebraic_bnd_node_range = std::make_unique<ConstBndNodeRange>(*range);
 }
+
+unsigned short
+FEProblemBase::getCurrentICState()
+{
+  return _current_ic_state;
+}
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/current_state_ic.i b/modules/solid_mechanics/test/tests/old_state_ic/current_state_ic.i
new file mode 100644
index 000000000000..ce5741b200dd
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/current_state_ic.i
@@ -0,0 +1,71 @@
+[Mesh]
+  type = GeneratedMesh
+  dim = 2
+  nx = 1
+  ny = 1
+[]
+
+[Variables]
+  [disp_x]
+  []
+[]
+
+[AuxVariables]
+  [old_disp_x]
+  []
+[]
+
+[Kernels]
+  [ifx]
+    type = InertialForce
+    variable = disp_x
+    density = 1
+    use_displaced_mesh = false
+  []
+[]
+
+[AuxKernels]
+  [old_disp_x]
+    type = CopyValueAux
+    variable = old_disp_x
+    source = 'disp_x'
+    state = OLD
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[ICs]
+  [current]
+    type = ConstantIC
+    variable = disp_x
+    value = 7
+    state = CURRENT
+  []
+[]
+
+[Postprocessors]
+  [disp_x]
+    type = ElementAverageValue
+    variable = disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [old_disp_x]
+    type = ElementAverageValue
+    variable = old_disp_x
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[Executioner]
+  type = Transient
+  [TimeIntegrator]
+    type = CentralDifference
+    solve_type = lumped
+  []
+  solve_type = LINEAR
+  num_steps = 0
+[]
+
+[Outputs]
+  csv = true
+[]
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/error_same_ic.i b/modules/solid_mechanics/test/tests/old_state_ic/error_same_ic.i
new file mode 100644
index 000000000000..fc4123002944
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/error_same_ic.i
@@ -0,0 +1,109 @@
+[Mesh]
+  type = GeneratedMesh
+  dim = 2
+  nx = 1
+  ny = 1
+[]
+
+[Variables]
+  [disp_x]
+  []
+[]
+
+[AuxVariables]
+  [vel_x]
+  []
+  [acc_x]
+  []
+  [old_disp_x]
+  []
+  [older_disp_x]
+  []
+[]
+
+[Kernels]
+  [ifx]
+    type = InertialForce
+    variable = disp_x
+    density = 1
+    use_displaced_mesh = false
+  []
+[]
+
+[AuxKernels]
+  [vel_x]
+    type = TestNewmarkTI
+    variable = vel_x
+    displacement = disp_x
+    first = true
+    execute_on = 'LINEAR TIMESTEP_END'
+  []
+  [acc_x]
+    type = TestNewmarkTI
+    variable = acc_x
+    displacement = disp_x
+    first = false
+    execute_on = 'LINEAR TIMESTEP_END'
+  []
+  [old_disp_x]
+    type = CopyValueAux
+    variable = old_disp_x
+    source = 'disp_x'
+    state = OLD
+    execute_on = 'initial timestep_end'
+  []
+  [older_disp_x]
+    type = CopyValueAux
+    variable = older_disp_x
+    source = 'disp_x'
+    state = OLDER
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[ICs]
+  [current]
+    type = ConstantIC
+    variable = disp_x
+    value = 7
+    state = CURRENT
+  []
+  [old]
+    type = ConstantIC
+    variable = disp_x
+    value = 7
+    state = CURRENT
+  []
+[]
+
+[Postprocessors]
+  [disp_x]
+    type = ElementAverageValue
+    variable = disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [old_disp_x]
+    type = ElementAverageValue
+    variable = old_disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [older_disp_x]
+    type = ElementAverageValue
+    variable = older_disp_x
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[Executioner]
+  type = Transient
+  [TimeIntegrator]
+    type = CentralDifference
+    solve_type = lumped
+  []
+  solve_type = LINEAR
+  num_steps = 0
+[]
+
+[Outputs]
+  csv = true
+[]
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/gold/current_state_ic_out.csv b/modules/solid_mechanics/test/tests/old_state_ic/gold/current_state_ic_out.csv
new file mode 100644
index 000000000000..656d776c6c5b
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/gold/current_state_ic_out.csv
@@ -0,0 +1,2 @@
+time,disp_x,old_disp_x
+0,7,7
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/gold/old_state_ic_out.csv b/modules/solid_mechanics/test/tests/old_state_ic/gold/old_state_ic_out.csv
new file mode 100644
index 000000000000..9be265005e2e
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/gold/old_state_ic_out.csv
@@ -0,0 +1,2 @@
+time,disp_x,old_disp_x,older_disp_x
+0,0,-1,-3
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/gold/velocity_ic_out.csv b/modules/solid_mechanics/test/tests/old_state_ic/gold/velocity_ic_out.csv
new file mode 100644
index 000000000000..d3d5fa4d5fe4
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/gold/velocity_ic_out.csv
@@ -0,0 +1,4 @@
+time,disp_x,vel_x
+0,0,0
+1,1,1
+2,2,1
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/old_state_ic.i b/modules/solid_mechanics/test/tests/old_state_ic/old_state_ic.i
new file mode 100644
index 000000000000..7a85e56ee5a0
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/old_state_ic.i
@@ -0,0 +1,115 @@
+[Mesh]
+  type = GeneratedMesh
+  dim = 2
+  nx = 1
+  ny = 1
+[]
+
+[Variables]
+  [disp_x]
+  []
+[]
+
+[AuxVariables]
+  [vel_x]
+  []
+  [acc_x]
+  []
+  [old_disp_x]
+  []
+  [older_disp_x]
+  []
+[]
+
+[Kernels]
+  [ifx]
+    type = InertialForce
+    variable = disp_x
+    density = 1
+    use_displaced_mesh = false
+  []
+[]
+
+[AuxKernels]
+  [vel_x]
+    type = TestNewmarkTI
+    variable = vel_x
+    displacement = disp_x
+    first = true
+    execute_on = 'LINEAR TIMESTEP_END'
+  []
+  [acc_x]
+    type = TestNewmarkTI
+    variable = acc_x
+    displacement = disp_x
+    first = false
+    execute_on = 'LINEAR TIMESTEP_END'
+  []
+  [old_disp_x]
+    type = CopyValueAux
+    variable = old_disp_x
+    source = 'disp_x'
+    state = OLD
+    execute_on = 'initial timestep_end'
+  []
+  [older_disp_x]
+    type = CopyValueAux
+    variable = older_disp_x
+    source = 'disp_x'
+    state = OLDER
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[ICs]
+  [current]
+    type = ConstantIC
+    variable = disp_x
+    value = 0
+    state = CURRENT
+  []
+  [old]
+    type = ConstantIC
+    variable = disp_x
+    value = -1
+    state = OLD
+  []
+  [older]
+    type = ConstantIC
+    variable = disp_x
+    value = -3
+    state = OLDER
+  []
+[]
+
+[Postprocessors]
+  [disp_x]
+    type = ElementAverageValue
+    variable = disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [old_disp_x]
+    type = ElementAverageValue
+    variable = old_disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [older_disp_x]
+    type = ElementAverageValue
+    variable = older_disp_x
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[Executioner]
+  type = Transient
+  [TimeIntegrator]
+    type = CentralDifference
+    solve_type = lumped
+  []
+  solve_type = LINEAR
+  num_steps = 0
+[]
+
+[Outputs]
+  csv = true
+[]
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/tests b/modules/solid_mechanics/test/tests/old_state_ic/tests
new file mode 100644
index 000000000000..317246ba048d
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/tests
@@ -0,0 +1,28 @@
+[Tests]
+  issues = '#28073'
+  design = "syntax/ICs/index.md"
+  [old_state_ic]
+    type = CSVDiff
+    input = 'old_state_ic.i'
+    csvdiff = 'old_state_ic_out.csv'
+    requirement = 'The system shall be able to set initial conditions for old states of the solution.'
+  []
+  [current_state_ic]
+    type = CSVDiff
+    input = 'current_state_ic.i'
+    csvdiff = 'current_state_ic_out.csv'
+    requirement = 'When only current state is specified with an initial condition, the old state should equal the current state.'
+  []
+  [velocity_ic]
+    type = CSVDiff
+    input = 'velocity_ic.i'
+    csvdiff = 'velocity_ic_out.csv'
+    requirement = 'The system shall be able to set initial conditions for old states, which enables an initial velocity condition for explicit dynamics.'
+  []
+  [error_same_ic]
+    type = RunException
+    input = 'error_same_ic.i'
+    expect_err = "The initial condition 'old' is being defined on a block that already has an initial condition defined with the same variable and state."
+    requirement = 'Should throw error for same IC.'
+  []
+[]
diff --git a/modules/solid_mechanics/test/tests/old_state_ic/velocity_ic.i b/modules/solid_mechanics/test/tests/old_state_ic/velocity_ic.i
new file mode 100644
index 000000000000..c7cc4c411c05
--- /dev/null
+++ b/modules/solid_mechanics/test/tests/old_state_ic/velocity_ic.i
@@ -0,0 +1,79 @@
+[Mesh]
+  type = GeneratedMesh
+  dim = 2
+  nx = 1
+  ny = 1
+[]
+
+[Variables]
+  [disp_x]
+  []
+[]
+
+[AuxVariables]
+  [vel_x]
+  []
+  [acc_x]
+  []
+[]
+
+[Kernels]
+  [ifx]
+    type = InertialForce
+    variable = disp_x
+    density = 1
+    use_displaced_mesh = false
+  []
+[]
+
+[AuxKernels]
+  [vel_x]
+    type = TestNewmarkTI
+    variable = vel_x
+    displacement = disp_x
+    first = true
+    execute_on = 'INITIAL LINEAR TIMESTEP_BEGIN TIMESTEP_END'
+  []
+[]
+
+[ICs]
+  [current]
+    type = ConstantIC
+    variable = disp_x
+    value = 0
+    state = CURRENT
+  []
+  [old]
+    type = ConstantIC
+    variable = disp_x
+    value = -1
+    state = OLD
+  []
+[]
+
+[Postprocessors]
+  [disp_x]
+    type = ElementAverageValue
+    variable = disp_x
+    execute_on = 'initial timestep_end'
+  []
+  [vel_x]
+    type = ElementAverageValue
+    variable = vel_x
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[Executioner]
+  type = Transient
+  [TimeIntegrator]
+    type = CentralDifference
+    solve_type = lumped
+  []
+  solve_type = LINEAR
+  num_steps = 2
+[]
+
+[Outputs]
+  csv = true
+[]
diff --git a/test/tests/auxkernels/copy_value_aux/copy_old_aux.i b/test/tests/auxkernels/copy_value_aux/copy_old_aux.i
new file mode 100644
index 000000000000..fd2d76a92c86
--- /dev/null
+++ b/test/tests/auxkernels/copy_value_aux/copy_old_aux.i
@@ -0,0 +1,87 @@
+[Mesh]
+  type = GeneratedMesh
+  dim = 2
+  nx = 1
+  ny = 1
+[]
+
+[Variables]
+  [T]
+  []
+[]
+
+[AuxVariables]
+  [T_old]
+  []
+  [T_older]
+  []
+[]
+
+[Kernels]
+  [hctd]
+    type = TimeDerivative
+    variable = T
+  []
+  [hs]
+    type = BodyForce
+    variable = T
+    value = 1
+  []
+[]
+
+[AuxKernels]
+  [T_old]
+    type = CopyValueAux
+    variable = T_old
+    source = T
+    state = OLD
+    execute_on = 'initial timestep_end'
+  []
+  [T_older]
+    type = CopyValueAux
+    variable = T_older
+    source = T
+    state = OLDER
+    execute_on = 'initial timestep_end'
+  []
+[]
+
+[ICs]
+  [T]
+    type = ConstantIC
+    variable = T
+    value = 0
+  []
+[]
+
+[Postprocessors]
+  [T]
+    type = ElementAverageValue
+    variable = T
+    execute_on = 'timestep_end'
+  []
+  [T_old]
+    type = ElementAverageValue
+    variable = T_old
+    execute_on = 'timestep_end'
+  []
+  [T_older]
+    type = ElementAverageValue
+    variable = T_older
+    execute_on = 'timestep_end'
+  []
+[]
+
+[Executioner]
+  type = Transient
+  [TimeIntegrator]
+    type = ActuallyExplicitEuler
+    solve_type = lumped
+  []
+  solve_type = LINEAR
+  num_steps = 3
+[]
+
+[Outputs]
+  csv = true
+[]
diff --git a/test/tests/auxkernels/copy_value_aux/gold/copy_old_aux_out.csv b/test/tests/auxkernels/copy_value_aux/gold/copy_old_aux_out.csv
new file mode 100644
index 000000000000..fab4bd0ec99e
--- /dev/null
+++ b/test/tests/auxkernels/copy_value_aux/gold/copy_old_aux_out.csv
@@ -0,0 +1,5 @@
+time,T,T_old,T_older
+0,0,0,0
+1,1,0,0
+2,2,1,0
+3,3,2,1
diff --git a/test/tests/auxkernels/copy_value_aux/tests b/test/tests/auxkernels/copy_value_aux/tests
index dcc75dd87603..0895249baedc 100644
--- a/test/tests/auxkernels/copy_value_aux/tests
+++ b/test/tests/auxkernels/copy_value_aux/tests
@@ -8,4 +8,10 @@
     requirement = "The system shall be able to copy from a variable to another of the same finite "
                   "element family and order.  "
   []
+  [copy_old]
+    type = CSVDiff
+    input = copy_old_aux.i
+    csvdiff = copy_old_aux_out.csv
+    requirement = "The system shall be able to copy from a variable OLD and OLDER state to an AuxVariable."
+  []
 []