prima delay calc
Signed-off-by: James Cherry <cherry@parallaxsw.com>
This commit is contained in:
parent
37a1236449
commit
40f8453dc3
|
|
@ -80,6 +80,7 @@ set(STA_SOURCE
|
|||
dcalc/LumpedCapDelayCalc.cc
|
||||
dcalc/NetCaps.cc
|
||||
dcalc/ParallelDelayCalc.cc
|
||||
dcalc/PrimaDelayCalc.cc
|
||||
dcalc/UnitDelayCalc.cc
|
||||
|
||||
graph/DelayFloat.cc
|
||||
|
|
|
|||
|
|
@ -24,6 +24,7 @@
|
|||
#include "ArnoldiDelayCalc.hh"
|
||||
#include "CcsCeffDelayCalc.hh"
|
||||
#include "CcsSimDelayCalc.hh"
|
||||
#include "PrimaDelayCalc.hh"
|
||||
|
||||
namespace sta {
|
||||
|
||||
|
|
@ -41,6 +42,7 @@ registerDelayCalcs()
|
|||
registerDelayCalc("arnoldi", makeArnoldiDelayCalc);
|
||||
registerDelayCalc("ccs_ceff", makeCcsCeffDelayCalc);
|
||||
registerDelayCalc("ccs_sim", makeCcsSimDelayCalc);
|
||||
registerDelayCalc("prima", makePrimaDelayCalc);
|
||||
}
|
||||
|
||||
void
|
||||
|
|
|
|||
|
|
@ -21,6 +21,7 @@
|
|||
#include "Sta.hh"
|
||||
#include "ArcDelayCalc.hh"
|
||||
#include "dcalc/ArcDcalcWaveforms.hh"
|
||||
#include "dcalc/PrimaDelayCalc.hh"
|
||||
|
||||
%}
|
||||
|
||||
|
|
@ -133,4 +134,16 @@ ccs_load_waveform(const Pin *in_pin,
|
|||
return Table1();
|
||||
}
|
||||
|
||||
void
|
||||
set_prima_reduce_order(size_t order)
|
||||
{
|
||||
cmdLinkedNetwork();
|
||||
Sta *sta = Sta::sta();
|
||||
PrimaDelayCalc *dcalc = dynamic_cast<PrimaDelayCalc*>(sta->arcDelayCalc());
|
||||
if (dcalc) {
|
||||
dcalc->setPrimaReduceOrder(order);
|
||||
sta->delaysInvalid();
|
||||
}
|
||||
}
|
||||
|
||||
%} // inline
|
||||
|
|
|
|||
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,263 @@
|
|||
// OpenSTA, Static Timing Analyzer
|
||||
// Copyright (c) 2024, Parallax Software, Inc.
|
||||
//
|
||||
// This program is free software: you can redistribute it and/or modify
|
||||
// it under the terms of the GNU General Public License as published by
|
||||
// the Free Software Foundation, either version 3 of the License, or
|
||||
// (at your option) any later version.
|
||||
//
|
||||
// This program is distributed in the hope that it will be useful,
|
||||
// but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
// GNU General Public License for more details.
|
||||
//
|
||||
// You should have received a copy of the GNU General Public License
|
||||
// along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <map>
|
||||
#include <Eigen/SparseCore>
|
||||
#include <Eigen/SparseLU>
|
||||
|
||||
#include "Map.hh"
|
||||
#include "LumpedCapDelayCalc.hh"
|
||||
#include "ArcDcalcWaveforms.hh"
|
||||
|
||||
namespace sta {
|
||||
|
||||
class ArcDelayCalc;
|
||||
class StaState;
|
||||
class Corner;
|
||||
|
||||
using std::vector;
|
||||
using std::array;
|
||||
using Eigen::MatrixXd;
|
||||
using Eigen::MatrixXcd;
|
||||
using Eigen::VectorXd;
|
||||
using Eigen::SparseMatrix;
|
||||
using Eigen::Index;
|
||||
using std::map;
|
||||
|
||||
typedef Map<const Pin*, size_t, PinIdLess> PinNodeMap;
|
||||
typedef Map<const ParasiticNode*, size_t> NodeIndexMap;
|
||||
typedef Map<const Pin*, size_t> PortIndexMap;
|
||||
typedef SparseMatrix<double> MatrixSd;
|
||||
typedef Map<const Pin*, VectorXd, PinIdLess> PinLMap;
|
||||
typedef map<const Pin*, FloatSeq, PinIdLess> WatchPinValuesMap;
|
||||
|
||||
typedef Table1 Waveform;
|
||||
|
||||
ArcDelayCalc *
|
||||
makePrimaDelayCalc(StaState *sta);
|
||||
|
||||
class PrimaDelayCalc : public DelayCalcBase,
|
||||
public ArcDcalcWaveforms
|
||||
{
|
||||
public:
|
||||
PrimaDelayCalc(StaState *sta);
|
||||
PrimaDelayCalc(const PrimaDelayCalc &dcalc);
|
||||
~PrimaDelayCalc();
|
||||
ArcDelayCalc *copy() override;
|
||||
void copyState(const StaState *sta) override;
|
||||
void setPrimaReduceOrder(size_t order);
|
||||
Parasitic *findParasitic(const Pin *drvr_pin,
|
||||
const RiseFall *rf,
|
||||
const DcalcAnalysisPt *dcalc_ap) override;
|
||||
Parasitic *reduceParasitic(const Parasitic *parasitic_network,
|
||||
const Pin *drvr_pin,
|
||||
const RiseFall *rf,
|
||||
const DcalcAnalysisPt *dcalc_ap) override;
|
||||
ArcDcalcResult inputPortDelay(const Pin *drvr_pin,
|
||||
float in_slew,
|
||||
const RiseFall *rf,
|
||||
const Parasitic *parasitic,
|
||||
const LoadPinIndexMap &load_pin_index_map,
|
||||
const DcalcAnalysisPt *dcalc_ap) override;
|
||||
ArcDcalcResult gateDelay(const Pin *drvr_pin,
|
||||
const TimingArc *arc,
|
||||
const Slew &in_slew,
|
||||
float load_cap,
|
||||
const Parasitic *parasitic,
|
||||
const LoadPinIndexMap &load_pin_index_map,
|
||||
const DcalcAnalysisPt *dcalc_ap) override;
|
||||
ArcDcalcResultSeq gateDelays(ArcDcalcArgSeq &dcalc_args,
|
||||
float load_cap,
|
||||
const LoadPinIndexMap &load_pin_index_map,
|
||||
const DcalcAnalysisPt *dcalc_ap) override;
|
||||
string reportGateDelay(const Pin *drvr_pin,
|
||||
const TimingArc *arc,
|
||||
const Slew &in_slew,
|
||||
float load_cap,
|
||||
const Parasitic *parasitic,
|
||||
const LoadPinIndexMap &load_pin_index_map,
|
||||
const DcalcAnalysisPt *dcalc_ap,
|
||||
int digits) override;
|
||||
|
||||
// Record waveform for drvr/load pin.
|
||||
void watchPin(const Pin *pin);
|
||||
void clearWatchPins();
|
||||
PinSeq watchPins() const;
|
||||
Waveform watchWaveform(const Pin *pin);
|
||||
|
||||
Waveform inputWaveform(const Pin *in_pin,
|
||||
const RiseFall *in_rf,
|
||||
const Corner *corner,
|
||||
const MinMax *min_max) override;
|
||||
Waveform drvrWaveform(const Pin *in_pin,
|
||||
const RiseFall *in_rf,
|
||||
const Pin *drvr_pin,
|
||||
const RiseFall *drvr_rf,
|
||||
const Corner *corner,
|
||||
const MinMax *min_max) override;
|
||||
Waveform loadWaveform(const Pin *in_pin,
|
||||
const RiseFall *in_rf,
|
||||
const Pin *drvr_pin,
|
||||
const RiseFall *drvr_rf,
|
||||
const Pin *load_pin,
|
||||
const Corner *corner,
|
||||
const MinMax *min_max) override;
|
||||
|
||||
protected:
|
||||
ArcDcalcResultSeq tableDcalcResults(float load_cap);
|
||||
void simulate();
|
||||
void simulate1(const MatrixSd &G,
|
||||
const MatrixSd &C,
|
||||
const MatrixXd &B,
|
||||
const VectorXd &x_init,
|
||||
const MatrixXd &x_to_v,
|
||||
const size_t order);
|
||||
double maxTime();
|
||||
double timeStep();
|
||||
float driverResistance();
|
||||
void updateCeffIdrvr();
|
||||
void initSim();
|
||||
void findLoads();
|
||||
void findNodeCount();
|
||||
void setOrder();
|
||||
void initCeffIdrvr();
|
||||
void setXinit();
|
||||
void stampEqns();
|
||||
void stampConductance(size_t n1,
|
||||
double g);
|
||||
void stampConductance(size_t n1,
|
||||
size_t n2,
|
||||
double g);
|
||||
void stampCapacitance(size_t n1,
|
||||
double cap);
|
||||
void stampCapacitance(size_t n1,
|
||||
size_t n2,
|
||||
double cap);
|
||||
float pinCapacitance(ParasiticNode *node);
|
||||
void setPortCurrents();
|
||||
void measureThresholds(double time);
|
||||
double voltage(const Pin *pin);
|
||||
double voltage(size_t node_idx);
|
||||
double voltagePrev(size_t node_idx);
|
||||
bool loadWaveformsFinished();
|
||||
ArcDcalcResultSeq dcalcResults();
|
||||
|
||||
void recordWaveformStep(double time);
|
||||
void makeWaveforms(const Pin *in_pin,
|
||||
const RiseFall *in_rf,
|
||||
const Pin *drvr_pin,
|
||||
const RiseFall *drvr_rf,
|
||||
const Pin *load_pin,
|
||||
const Corner *corner,
|
||||
const MinMax *min_max);
|
||||
void primaReduce();
|
||||
void primaReduce2();
|
||||
|
||||
void reportMatrix(const char *name,
|
||||
MatrixSd &matrix);
|
||||
void reportMatrix(const char *name,
|
||||
MatrixXd &matrix);
|
||||
void reportMatrix(const char *name,
|
||||
VectorXd &matrix);
|
||||
void reportVector(const char *name,
|
||||
vector<double> &matrix);
|
||||
void reportMatrix(MatrixSd &matrix);
|
||||
void reportMatrix(MatrixXd &matrix);
|
||||
void reportMatrix(VectorXd &matrix);
|
||||
void reportVector(vector<double> &matrix);
|
||||
|
||||
ArcDcalcArgSeq *dcalc_args_;
|
||||
size_t drvr_count_;
|
||||
float load_cap_;
|
||||
const DcalcAnalysisPt *dcalc_ap_;
|
||||
const Parasitic *parasitic_network_;
|
||||
const RiseFall *drvr_rf_;
|
||||
const LoadPinIndexMap *load_pin_index_map_;
|
||||
|
||||
PinNodeMap pin_node_map_; // Parasitic pin -> array index
|
||||
NodeIndexMap node_index_map_; // Parasitic node -> array index
|
||||
vector<OutputWaveforms*> output_waveforms_;
|
||||
double resistance_sum_;
|
||||
|
||||
vector<double> node_capacitances_;
|
||||
bool includes_pin_caps_;
|
||||
float coupling_cap_multiplier_;
|
||||
|
||||
size_t node_count_; // Parasitic network node count
|
||||
size_t port_count_; // aka drvr_count_
|
||||
size_t order_; // node_count_ + port_count_
|
||||
|
||||
// MNA node eqns
|
||||
// G*x(t) + C*x'(t) = B*u(t)
|
||||
MatrixSd G_;
|
||||
MatrixSd C_;
|
||||
MatrixXd B_;
|
||||
VectorXd x_init_;
|
||||
VectorXd u_;
|
||||
|
||||
// Prima reduced MNA eqns
|
||||
size_t prima_order_;
|
||||
MatrixXd Vq_;
|
||||
MatrixSd Gq_;
|
||||
MatrixSd Cq_;
|
||||
MatrixXd Bq_;
|
||||
VectorXd xq_init_;
|
||||
|
||||
// Node voltages.
|
||||
VectorXd v_; // voltage[node_idx]
|
||||
VectorXd v_prev_;
|
||||
|
||||
// Indexed by driver index.
|
||||
vector<double> ceff_;
|
||||
vector<double> drvr_current_;
|
||||
|
||||
double time_step_;
|
||||
double time_step_prev_;
|
||||
|
||||
// Waveform recording.
|
||||
bool make_waveforms_;
|
||||
const Pin *waveform_drvr_pin_;
|
||||
const Pin *waveform_load_pin_;
|
||||
FloatSeq drvr_voltages_;
|
||||
FloatSeq load_voltages_;
|
||||
WatchPinValuesMap watch_pin_values_;
|
||||
FloatSeq times_;
|
||||
|
||||
float vdd_;
|
||||
float vth_;
|
||||
float vl_;
|
||||
float vh_;
|
||||
|
||||
static constexpr size_t threshold_vl = 0;
|
||||
static constexpr size_t threshold_vth = 1;
|
||||
static constexpr size_t threshold_vh = 2;
|
||||
static constexpr size_t measure_threshold_count_ = 3;
|
||||
typedef array<double, measure_threshold_count_> ThresholdTimes;
|
||||
// Vl Vth Vh
|
||||
ThresholdTimes measure_thresholds_;
|
||||
// Indexed by node number.
|
||||
vector<ThresholdTimes> threshold_times_;
|
||||
|
||||
// Delay calculator to use when ccs waveforms are missing from liberty.
|
||||
ArcDelayCalc *table_dcalc_;
|
||||
|
||||
using ArcDelayCalc::reduceParasitic;
|
||||
};
|
||||
|
||||
} // namespacet
|
||||
|
|
@ -269,6 +269,7 @@ public:
|
|||
protected:
|
||||
void makeWireloadNetworkWorst(Parasitic *parasitic,
|
||||
const Pin *drvr_pin,
|
||||
const Net *net,
|
||||
float wireload_cap,
|
||||
float wireload_res,
|
||||
float fanout);
|
||||
|
|
|
|||
|
|
@ -203,7 +203,7 @@ Parasitics::makeWireloadNetwork(const Pin *drvr_pin,
|
|||
const MinMax *min_max,
|
||||
const ParasiticAnalysisPt *ap)
|
||||
{
|
||||
Net *net = network_->net(drvr_pin);
|
||||
const Net *net = findParasiticNet(drvr_pin);
|
||||
Parasitic *parasitic = makeParasiticNetwork(net, false, ap);
|
||||
const OperatingConditions *op_cond = sdc_->operatingConditions(min_max);
|
||||
float wireload_cap, wireload_res;
|
||||
|
|
@ -214,7 +214,7 @@ Parasitics::makeWireloadNetwork(const Pin *drvr_pin,
|
|||
tree = op_cond->wireloadTree();
|
||||
switch (tree) {
|
||||
case WireloadTree::worst_case:
|
||||
makeWireloadNetworkWorst(parasitic, drvr_pin, wireload_cap,
|
||||
makeWireloadNetworkWorst(parasitic, drvr_pin, net, wireload_cap,
|
||||
wireload_res, fanout);
|
||||
break;
|
||||
case WireloadTree::balanced:
|
||||
|
|
@ -235,12 +235,12 @@ Parasitics::makeWireloadNetwork(const Pin *drvr_pin,
|
|||
void
|
||||
Parasitics::makeWireloadNetworkWorst(Parasitic *parasitic,
|
||||
const Pin *drvr_pin,
|
||||
const Net *net,
|
||||
float wireload_cap,
|
||||
float wireload_res,
|
||||
float /* fanout */)
|
||||
{
|
||||
ParasiticNode *drvr_node = ensureParasiticNode(parasitic, drvr_pin, network_);
|
||||
Net *net = network_->net(drvr_pin);
|
||||
size_t resistor_index = 1;
|
||||
ParasiticNode *load_node = ensureParasiticNode(parasitic, net, 0, network_);
|
||||
makeResistor(parasitic, resistor_index++, wireload_res, drvr_node, load_node);
|
||||
|
|
|
|||
Binary file not shown.
Binary file not shown.
|
|
@ -0,0 +1,51 @@
|
|||
Warning: asap7_simple.lib.gz line 71510, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 71986, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 72462, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 72938, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 73414, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 74830, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 71029, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 71505, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 71981, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 72457, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 72933, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 73409, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 73885, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 82276, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 83692, when attribute inside table model.
|
||||
Warning: asap7_simple.lib.gz line 81795, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 82271, timing group from output port.
|
||||
Warning: asap7_simple.lib.gz line 82747, timing group from output port.
|
||||
Startpoint: r2 (rising edge-triggered flip-flop clocked by clk)
|
||||
Endpoint: r3 (rising edge-triggered flip-flop clocked by clk)
|
||||
Path Group: clk
|
||||
Path Type: max
|
||||
|
||||
Slew Delay Time Description
|
||||
----------------------------------------------------------------
|
||||
0.00 0.00 0.00 clock clk (rise edge)
|
||||
0.00 0.00 clock source latency
|
||||
10.00 0.00 0.00 ^ clk2 (in)
|
||||
48.15 12.04 12.04 ^ r2/CLK (DFFHQx4_ASAP7_75t_R)
|
||||
38.97 90.82 102.86 ^ r2/Q (DFFHQx4_ASAP7_75t_R)
|
||||
59.28 16.50 119.36 ^ u1/A (BUFx2_ASAP7_75t_R)
|
||||
70.25 51.69 171.05 ^ u1/Y (BUFx2_ASAP7_75t_R)
|
||||
83.74 18.32 189.37 ^ u2/B (AND2x2_ASAP7_75t_R)
|
||||
72.19 60.76 250.13 ^ u2/Y (AND2x2_ASAP7_75t_R)
|
||||
85.61 18.34 268.46 ^ r3/D (DFFHQx4_ASAP7_75t_R)
|
||||
268.46 data arrival time
|
||||
|
||||
0.00 500.00 500.00 clock clk (rise edge)
|
||||
0.00 500.00 clock source latency
|
||||
10.00 0.00 500.00 ^ clk3 (in)
|
||||
47.52 11.84 511.84 ^ r3/CLK (DFFHQx4_ASAP7_75t_R)
|
||||
0.00 511.84 clock reconvergence pessimism
|
||||
-14.89 496.95 library setup time
|
||||
496.95 data required time
|
||||
----------------------------------------------------------------
|
||||
496.95 data required time
|
||||
-268.46 data arrival time
|
||||
----------------------------------------------------------------
|
||||
228.48 slack (MET)
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,13 @@
|
|||
# prima reg1 asap7
|
||||
read_liberty asap7_invbuf.lib.gz
|
||||
read_liberty asap7_seq.lib.gz
|
||||
read_liberty asap7_simple.lib.gz
|
||||
read_verilog reg1_asap7.v
|
||||
link_design top
|
||||
create_clock -name clk -period 500 {clk1 clk2 clk3}
|
||||
set_input_delay -clock clk 1 {in1 in2}
|
||||
set_input_transition 10 {in1 in2 clk1 clk2 clk3}
|
||||
set_propagated_clock {clk1 clk2 clk3}
|
||||
read_spef reg1_asap7.spef
|
||||
sta::set_delay_calculator prima
|
||||
report_checks -fields {input_pins slew} -format full_clock
|
||||
|
|
@ -0,0 +1,135 @@
|
|||
*SPEF "IEEE 1481-1998"
|
||||
*DESIGN "reg1"
|
||||
*DATE "Fri Nov 20 13:23:00 2002"
|
||||
*VENDOR "Parallax Software, Inc"
|
||||
*PROGRAM "Handjob"
|
||||
*VERSION "1.0.1c"
|
||||
*DESIGN_FLOW "MISSING_NETS"
|
||||
*DIVIDER /
|
||||
*DELIMITER :
|
||||
*BUS_DELIMITER [ ]
|
||||
*T_UNIT 1.0 PS
|
||||
*C_UNIT 1.0 FF
|
||||
*R_UNIT 1.0 KOHM
|
||||
*L_UNIT 1.0 UH
|
||||
|
||||
*POWER_NETS VDD
|
||||
*GROUND_NETS VSS
|
||||
|
||||
*PORTS
|
||||
in1 I
|
||||
in2 I
|
||||
clk1 I
|
||||
clk2 I
|
||||
clk3 I
|
||||
out O
|
||||
|
||||
*D_NET in1 13.4
|
||||
*CONN
|
||||
*P in1 I
|
||||
*I r1:D I *L .0036
|
||||
*CAP
|
||||
1 in1 6.7
|
||||
2 r1:D 6.7
|
||||
*RES
|
||||
3 in1 r1:D 2.42
|
||||
*END
|
||||
|
||||
*D_NET in2 13.4
|
||||
*CONN
|
||||
*P in2 I
|
||||
*I r2:D I *L .0036
|
||||
*CAP
|
||||
1 in2 6.7
|
||||
2 r2:D 6.7
|
||||
*RES
|
||||
3 in2 r2:D 2.42
|
||||
*END
|
||||
|
||||
*D_NET clk1 13.4
|
||||
*CONN
|
||||
*P clk1 I
|
||||
*I r1:CLK I *L .0036
|
||||
*CAP
|
||||
1 clk1 6.7
|
||||
2 r1:CLK 6.7
|
||||
*RES
|
||||
3 clk1 r1:CLK 2.42
|
||||
*END
|
||||
|
||||
*D_NET clk2 13.4
|
||||
*CONN
|
||||
*P clk2 I
|
||||
*I r2:CLK I *L .0036
|
||||
*CAP
|
||||
1 clk2 6.7
|
||||
2 r2:CLK 6.7
|
||||
*RES
|
||||
3 clk2 r2:CLK 2.42
|
||||
*END
|
||||
|
||||
*D_NET clk3 13.4
|
||||
*CONN
|
||||
*P clk3 I
|
||||
*I r3:CLK I *L .0036
|
||||
*CAP
|
||||
1 clk3 6.7
|
||||
2 r3:CLK 6.7
|
||||
*RES
|
||||
3 clk3 r3:CLK 2.42
|
||||
*END
|
||||
|
||||
*D_NET r1q 13.4
|
||||
*CONN
|
||||
*I r1:Q O
|
||||
*I u2:A I *L .0086
|
||||
*CAP
|
||||
1 r1:Q 6.7
|
||||
2 u2:A 6.7
|
||||
*RES
|
||||
3 r1:Q u2:A 2.42
|
||||
*END
|
||||
|
||||
*D_NET r2q 13.4
|
||||
*CONN
|
||||
*I r2:Q O
|
||||
*I u1:A I *L .0086
|
||||
*CAP
|
||||
1 r2:Q 6.7
|
||||
2 u1:A 6.7
|
||||
*RES
|
||||
3 r2:Q u1:A 2.42
|
||||
*END
|
||||
|
||||
*D_NET u1z 13.4
|
||||
*CONN
|
||||
*I u1:Y O
|
||||
*I u2:B I *L .0086
|
||||
*CAP
|
||||
1 u1:Y 6.7
|
||||
2 u2:B 6.7
|
||||
*RES
|
||||
3 u1:Y u2:B 2.42
|
||||
*END
|
||||
|
||||
*D_NET u2z 13.4
|
||||
*CONN
|
||||
*I u2:Y O
|
||||
*I r3:D I *L .0086
|
||||
*CAP
|
||||
1 u2:Y 6.7
|
||||
2 r3:D 6.7
|
||||
*RES
|
||||
3 u2:Y r3:D 2.42
|
||||
*END
|
||||
|
||||
*D_NET out 13.4
|
||||
*CONN
|
||||
*I r3:Q O
|
||||
*P out O
|
||||
*CAP
|
||||
1 r3:Q 6.7
|
||||
2 out 6.7
|
||||
*RES
|
||||
3 r3:Q out 2.42
|
||||
*END
|
||||
|
|
@ -0,0 +1,11 @@
|
|||
module top (in1, in2, clk1, clk2, clk3, out);
|
||||
input in1, in2, clk1, clk2, clk3;
|
||||
output out;
|
||||
wire r1q, r2q, u1z, u2z;
|
||||
|
||||
DFFHQx4_ASAP7_75t_R r1 (.D(in1), .CLK(clk1), .Q(r1q));
|
||||
DFFHQx4_ASAP7_75t_R r2 (.D(in2), .CLK(clk2), .Q(r2q));
|
||||
BUFx2_ASAP7_75t_R u1 (.A(r2q), .Y(u1z));
|
||||
AND2x2_ASAP7_75t_R u2 (.A(r1q), .B(u1z), .Y(u2z));
|
||||
DFFHQx4_ASAP7_75t_R r3 (.D(u2z), .CLK(clk3), .Q(out));
|
||||
endmodule // top
|
||||
|
|
@ -123,6 +123,7 @@ record_example_tests {
|
|||
|
||||
record_sta_tests {
|
||||
ccs_sim1
|
||||
prima3
|
||||
verilog_attribute
|
||||
}
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue