Added ADC, H-Bridge and motor models, refactored project structure

This commit is contained in:
2018-07-28 09:45:49 +02:00
parent 100822810f
commit 38099e3fc6
61 changed files with 696 additions and 44 deletions

View File

@ -0,0 +1,77 @@
# library files
FILE(GLOB RiscVSCHeaders *.h */*.h)
FILE(GLOB RiscvSCSources sysc/*.cpp)
set(LIB_HEADERS ${RiscVSCHeaders} )
set(LIB_SOURCES ${RiscvSCSources} )
set(APP_HEADERS )
set(APP_SOURCES sc_main.cpp)
# Define two variables in order not to repeat ourselves.
set(LIBRARY_NAME platform)
## the following setting needs to be consistent with the library
#add_definitions(-DSC_DEFAULT_WRITER_POLICY=SC_MANY_WRITERS)
# Define the library
add_library(${LIBRARY_NAME} ${LIB_SOURCES})
set_target_properties(${LIBRARY_NAME} PROPERTIES
VERSION ${VERSION} # ${VERSION} was defined in the main CMakeLists.
FRAMEWORK FALSE
PUBLIC_HEADER "${LIB_HEADERS}" # specify the public headers
)
# This is a make target, so you can do a "make riscv-sc"
set(APPLICATION_NAME riscv.vp)
include_directories(${CONAN_INCLUDE_DIRS_SEASOCKS})
include_directories(${SystemC_INCLUDE_DIRS})
include_directories(${CCI_INCLUDE_DIRS})
link_directories(${SystemC_LIBRARY_DIR})
link_directories(${CCI_LIBRARY_DIR})
link_directories(${CONAN_LIB_DIRS_SEASOCKS})
add_executable(${APPLICATION_NAME} ${APP_SOURCES})
# Links the target exe against the libraries
target_link_libraries(${APPLICATION_NAME} ${LIBRARY_NAME})
target_link_libraries(${APPLICATION_NAME} riscv.sc)
target_link_libraries(${APPLICATION_NAME} riscv)
target_link_libraries(${APPLICATION_NAME} dbt-core)
target_link_libraries(${APPLICATION_NAME} softfloat)
target_link_libraries(${APPLICATION_NAME} sc-components)
target_link_libraries(${APPLICATION_NAME} ${CONAN_LIBS_SEASOCKS})
target_link_libraries(${APPLICATION_NAME} external)
target_link_libraries(${APPLICATION_NAME} ${llvm_libs})
target_link_libraries(${APPLICATION_NAME} ${CCI_LIBRARIES} )
target_link_libraries(${APPLICATION_NAME} ${SystemC_LIBRARIES} )
if(SCV_FOUND)
add_definitions(-DWITH_SCV)
include_directories(${SCV_INCLUDE_DIRS})
link_directories(${SCV_LIBRARY_DIRS})
target_link_libraries (${APPLICATION_NAME} ${SCV_LIBRARIES})
endif()
target_link_libraries(${APPLICATION_NAME} ${Boost_LIBRARIES} )
if (Tcmalloc_FOUND)
target_link_libraries(${APPLICATION_NAME} ${Tcmalloc_LIBRARIES})
endif(Tcmalloc_FOUND)
# Says how and where to install software
# Targets:
# * <prefix>/lib/<libraries>
# * header location after install: <prefix>/include/<project>/*.h
# * headers can be included by C++ code `#<project>/Bar.hpp>`
install(TARGETS ${LIBRARY_NAME} ${APPLICATION_NAME}
EXPORT ${PROJECT_NAME}Targets # for downstream dependencies
ARCHIVE DESTINATION lib COMPONENT libs # static lib
RUNTIME DESTINATION bin COMPONENT libs # binaries
LIBRARY DESTINATION lib COMPONENT libs # shared lib
FRAMEWORK DESTINATION bin COMPONENT libs # for mac
PUBLIC_HEADER DESTINATION incl/${PROJECT_NAME} COMPONENT devel # headers for mac (note the different component -> different package)
INCLUDES DESTINATION incl # headers
)

186
platform/src/sc_main.cpp Normal file
View File

@ -0,0 +1,186 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include <boost/program_options.hpp>
#include <iss/log_categories.h>
#include <sstream>
#include "scc/configurer.h"
#include "scc/report.h"
#include "scc/scv_tr_db.h"
#include "scc/tracer.h"
#include <cci_utils/broker.h>
#include <iss/jit/jit_helper.h>
#include "../incl/sysc/top/system.h"
using namespace sysc;
namespace po = boost::program_options;
namespace {
const size_t ERROR_IN_COMMAND_LINE = 1;
const size_t SUCCESS = 0;
const size_t ERROR_UNHANDLED_EXCEPTION = 2;
} // namespace
#include "sysc/kernel/sc_externs.h"
int
main( int argc, char* argv[]){
#ifdef _POSIX_SOURCE
putenv(const_cast<char*>("SC_SIGNAL_WRITE_CHECK=DISABLE"));
putenv(const_cast<char*>("SC_VCD_SCOPES=ENABLE"));
#endif
return sc_core::sc_elab_and_sim( argc, argv );
}
int sc_main(int argc, char *argv[]) {
// sc_report_handler::set_handler(my_report_handler);
scc::Logger<>::reporting_level() = logging::ERROR;
cci::cci_register_broker(new cci_utils::broker("Global Broker"));
///////////////////////////////////////////////////////////////////////////
// CLI argument parsing
///////////////////////////////////////////////////////////////////////////
po::options_description desc("Options");
// clang-format off
desc.add_options()
("help,h", "Print help message")
("verbose,v", po::value<int>()->implicit_value(3), "Sets logging verbosity")
("log-file", po::value<std::string>(), "Sets default log file.")
("disass,d", po::value<std::string>()->implicit_value(""), "Enables disassembly")
("elf,l", po::value<std::string>(), "ELF file to load")
("gdb-port,g", po::value<unsigned short>()->default_value(0), "enable gdb server and specify port to use")
("dump-ir", "dump the intermediate representation")
("quantum", po::value<unsigned>(), "SystemC quantum time in ns")
("reset,r", po::value<std::string>(), "reset address")
("trace,t", po::value<unsigned>()->default_value(0), "enable tracing, or combintation of 1=signals and 2=TX text, 4=TX compressed text, 6=TX in SQLite")
("max_time,m", po::value<std::string>(), "maximum time to run")
("config-file,c", po::value<std::string>()->default_value(""), "read configuration from file")
("dump-config", po::value<std::string>()->default_value(""), "dump configuration to file file");
// clang-format on
po::variables_map vm;
try {
po::store(po::parse_command_line(argc, argv, desc), vm); // can throw
// --help option
if (vm.count("help")) {
std::cout << "DBT-RISE-RiscV simulator for RISC-V" << std::endl << desc << std::endl;
return SUCCESS;
}
po::notify(vm); // throws on error, so do after help in case
// there are any problems
} catch (po::error &e) {
std::cerr << "ERROR: " << e.what() << std::endl << std::endl;
std::cerr << desc << std::endl;
return ERROR_IN_COMMAND_LINE;
}
if (vm.count("verbose")) {
auto l = logging::as_log_level(vm["verbose"].as<int>());
LOGGER(DEFAULT)::reporting_level() = l;
LOGGER(connection)::reporting_level() = l;
LOGGER(SystemC)::reporting_level() = l;
scc::Logger<>::reporting_level() = l;
}
if (vm.count("log-file")) {
// configure the connection logger
auto f = fopen(vm["log-file"].as<std::string>().c_str(), "w");
LOG_OUTPUT(DEFAULT)::stream() = f;
LOG_OUTPUT(connection)::stream() = f;
LOG_OUTPUT(SystemC)::stream() = f;
}
///////////////////////////////////////////////////////////////////////////
// set up infrastructure
///////////////////////////////////////////////////////////////////////////
iss::init_jit(argc, argv);
///////////////////////////////////////////////////////////////////////////
// set up configuration
///////////////////////////////////////////////////////////////////////////
scc::configurer cfg(vm["config-file"].as<std::string>());
///////////////////////////////////////////////////////////////////////////
// instantiate top level
///////////////////////////////////////////////////////////////////////////
auto i_system = std::make_unique<sysc::system>("i_system");
///////////////////////////////////////////////////////////////////////////
// set up tracing & transaction recording
///////////////////////////////////////////////////////////////////////////
auto trace_val = vm["trace"].as<unsigned>();
scc::tracer trace("simple_system", static_cast<scc::tracer::file_type>(trace_val >> 1), trace_val != 0);
///////////////////////////////////////////////////////////////////////////
// dump configuration if requested
///////////////////////////////////////////////////////////////////////////
if(vm["dump-config"].as<std::string>().size()>0){
std::ofstream of{vm["dump-config"].as<std::string>()};
if(of.is_open())
cfg.dump_configuration(of);
}
cfg.configure();
///////////////////////////////////////////////////////////////////////////
// overwrite config with command line settings
///////////////////////////////////////////////////////////////////////////
if (vm["gdb-port"].as<unsigned short>())
cfg.set_value("i_system.i_platform.i_core_complex.gdb_server_port", vm["gdb-port"].as<unsigned short>());
if (vm.count("dump-ir"))
cfg.set_value("i_system.i_platform.i_core_complex.dump_ir", vm.count("dump-ir") != 0);
if (vm.count("elf"))
cfg.set_value("i_system.i_platform.i_core_complex.elf_file", vm["elf"].as<std::string>());
if (vm.count("quantum"))
tlm::tlm_global_quantum::instance().set(sc_core::sc_time(vm["quantum"].as<unsigned>(), sc_core::SC_NS));
if (vm.count("reset")) {
auto str = vm["reset"].as<std::string>();
uint64_t start_address = str.find("0x") == 0 ? std::stoull(str.substr(2), 0, 16) : std::stoull(str, 0, 10);
cfg.set_value("i_system.i_platform.i_core_complex.reset_address", start_address);
}
if (vm.count("disass")) {
cfg.set_value("i_system.i_platform.i_core_complex.enable_disass", true);
LOGGER(disass)::reporting_level() = logging::INFO;
auto file_name = vm["disass"].as<std::string>();
if (file_name.length() > 0) {
LOG_OUTPUT(disass)::stream() = fopen(file_name.c_str(), "w");
LOGGER(disass)::print_time() = false;
LOGGER(disass)::print_severity() = false;
}
}
///////////////////////////////////////////////////////////////////////////
// run simulation
///////////////////////////////////////////////////////////////////////////
try {
if(vm.count("max_time")){
sc_core::sc_time max_time = scc::parse_from_string(vm["max_time"].as<std::string>());
sc_core::sc_start(max_time);
} else
sc_core::sc_start();
} catch(sc_core::sc_report& rep){
CLOG(FATAL, SystemC)<<"IWEF"[rep.get_severity()]<<"("<<rep.get_id()<<") "<<rep.get_msg_type()<<": "<<rep.get_msg()<<std::endl;
}
if (!sc_core::sc_end_of_simulation_invoked()) sc_core::sc_stop();
return 0;
}

164
platform/src/sysc/BLDC.cpp Normal file
View File

@ -0,0 +1,164 @@
/*
* BLDC.cpp
*
* Created on: 26.06.2018
* Author: eyck
*/
#include "sysc/top/BLDC.h"
// implementation according to Modeling of BLDC Motor with Ideal Back-EMF for Automotive Applications
// Proceedings of the World Congress on Engineering 2011 Vol II WCE 2011, July 6 - 8, 2011, London, U.K.
BLDC::BLDC(const Config config)
: config(config)
, stateVector({{0.0, 0.0, 0.0, 0.0, 0.0}})
, state(stateVector)
, vin({{0.0, 0.0, 0.0}})
, voltages({{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}})
{
state.init();
}
BLDC::~BLDC() {
}
double BLDC::calc_bemf_factor(const State& x, double theta){
if(theta>=0 && theta < 2./3.*M_PI){
return 1;
} else if(theta>=2./3.*M_PI && theta < M_PI){
return 1-6/M_PI*(theta-2./3.*M_PI);
} else if(theta>=M_PI && theta < 5./3. * M_PI){
return -1;
} else if(theta>=5./3. * M_PI && theta < 2. * M_PI){
return -1+6/M_PI*(theta-5./3.*M_PI);
} else {
fprintf(stderr, "ERROR: angle out of bounds can not calculate bemf %f\n", theta);
throw std::runtime_error("angle out of bounds can not calculate bemf");
}
}
void BLDC::calc_back_emf(const State& state, double theta_e) {
double max_bemf = config.Ke * state.omega;
voltages[EA] = max_bemf*calc_bemf_factor(state, norm_angle(theta_e));
voltages[EB] = max_bemf*calc_bemf_factor(state, norm_angle(theta_e + M_PI * (2. / 3.)));
voltages[EC] = max_bemf*calc_bemf_factor(state, norm_angle(theta_e + M_PI * (4. / 3.)));
}
void BLDC::calc_voltages(){
const double NaN = nan("");
/* Check which phases are excited. */
bool pa = isnan(vin[0])?false:true;
bool pb = isnan(vin[1])?false:true;
bool pc = isnan(vin[2])?false:true;
if (pa && pb && pc) {
voltages[VA] = vin[0];
voltages[VB] = vin[1];
voltages[VC] = vin[2];
voltages[VCENTER] = (voltages[VA] + voltages[VB] + voltages[VC] - voltages[EA] - voltages[EB] - voltages[EC]) / 3.;
} else if (pa && pb) {
voltages[VA] = vin[0];
voltages[VB] = vin[1];
voltages[VCENTER] = (voltages[VA] + voltages[VB] - voltages[EA] - voltages[EB]) / 2.;
voltages[VC] = voltages[EC] + voltages[VCENTER];
} else if (pa && pc) {
voltages[VA] = vin[0];
voltages[VC] = vin[2];
voltages[VCENTER] = (voltages[VA] + voltages[VC] - voltages[EA] - voltages[EC]) / 2.;
voltages[VB] = voltages[EB] + voltages[VCENTER];
} else if (pb && pc) {
voltages[VB] = vin[1];
voltages[VC] = vin[2];
voltages[VCENTER] = (voltages[VB] + voltages[VC] - voltages[EB] - voltages[EC]) / 2.;
voltages[VA] = voltages[EA] + voltages[VCENTER];
} else if (pa) {
voltages[VA] = vin[0];
voltages[VCENTER] = (voltages[VA] - voltages[EA]);
voltages[VB] = voltages[EB] + voltages[VCENTER];
voltages[VC] = voltages[EC] + voltages[VCENTER];
} else if (pb) {
voltages[VB] = vin[1];
voltages[VCENTER] = (voltages[VB] - voltages[EB]);
voltages[VA] = voltages[EA] + voltages[VCENTER];
voltages[VC] = voltages[EC] + voltages[VCENTER];
} else if (pc) {
voltages[VC] = vin[0];
voltages[VCENTER] = (voltages[VC] - voltages[EC]);
voltages[VA] = voltages[EA] + voltages[VCENTER];
voltages[VB] = voltages[EB] + voltages[VCENTER];
} else {
voltages[VA] = voltages[EA];
voltages[VB] = voltages[EB];
voltages[VC] = voltages[EC];
voltages[VCENTER] = 0;
}
}
void BLDC::printToStream(std::ostream& os) const {
os<<state.omega<<";"<<state.theta<<";"
<<state.ia<<";"<<state.ib<<";"<<state.ic<<";"
<<voltages[VA]<<";"<<voltages[VB]<<";"<<voltages[VC]<<";"
<<voltages[EA]<<";"<<voltages[EB]<<";"<<voltages[EC]<<";"<<voltages[VCENTER]<<";"
<<vin[0]<<";"<<vin[1]<<";"<<vin[2]<<";"<<etorque;
}
void BLDC::rotor_dyn(const StateVector& x_, StateVector& dxdt_, const double t) {
const State x(const_cast<StateVector&>(x_));
State dxdt(dxdt_);
double theta_e = state.theta * (config.NbPoles / 2.);
/* Calculate backemf voltages. */
calc_back_emf(x, theta_e);
/* Calculate voltages. */
calc_voltages();
/* Electromagnetic torque. */
// if (x.omega == 0) {
// printf("ERROR: input state vector omega equals 0!!!\n");
// throw std::runtime_error("input state vector omega equals 0");
// }
/* electrical torque */
//etorque = ((voltages[EA] * x.ia) + (voltages[EB] * x.ib) + (voltages[EC] * x.ic)) / x.omega;
// which is equivalent to:
etorque = config.Ke*(
x.ia * (calc_bemf_factor(state, norm_angle(theta_e))) +
x.ib * (calc_bemf_factor(state, norm_angle(theta_e + M_PI * (2. / 3.)))) +
x.ic * (calc_bemf_factor(state, norm_angle(theta_e + M_PI * (4. / 3.))))
);
/* Mechanical torque. */
mtorque = ((etorque * (config.NbPoles / 2)) - (config.damping * x.omega) - torque_load);
if ((mtorque > 0) && (mtorque <= config.static_friction)) {
mtorque = 0;
} else if (mtorque > config.static_friction) {
mtorque -= config.static_friction;
} else if ((mtorque < 0) && (mtorque >= -(config.static_friction))) {
mtorque = 0;
} else if (mtorque < -(config.static_friction)) {
mtorque += config.static_friction;
}
/* Position of the rotor */
dxdt.theta = x.omega;
/* Acceleration of the rotor. (omega_dot) */
// a=M/J with M->torque, J->Inertia, a->angular acceleration
dxdt.omega = mtorque / config.inertia;
/* Calculate dot currents. */
dxdt.ia = (voltages[VA] - (config.R * x.ia) - voltages[EA] - voltages[VCENTER]) / (config.L - config.M);
dxdt.ib = (voltages[VB] - (config.R * x.ib) - voltages[EB] - voltages[VCENTER]) / (config.L - config.M);
dxdt.ic = (voltages[VC] - (config.R * x.ic) - voltages[EC] - voltages[VCENTER]) / (config.L - config.M);
}
void BLDC::run(double incr) {
if(dt>incr) throw std::runtime_error("incr needs to be larger than dt");
double next_time = current_time+incr;
odeint::integrate_adaptive(make_controlled( 1.0e-10 , 1.0e-6 , stepper_type() ),
[this]( const StateVector &x , StateVector &dxdt , double t ) {this->rotor_dyn(x, dxdt,t);},
stateVector, current_time, next_time, dt);
current_time=next_time;
state.theta=norm_angle(state.theta);
}
std::ostream& operator <<(std::ostream& os, const BLDC& bldc) {
bldc.printToStream(os);
return os;
}

83
platform/src/sysc/aon.cpp Normal file
View File

@ -0,0 +1,83 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/aon.h"
#include "scc/utilities.h"
#include "sysc/SiFive/gen/aon_regs.h"
namespace sysc {
aon::aon(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(clk_i)
, NAMED(erst_n_i)
, NAMED(lfclkc_o)
, NAMED(rst_o)
, NAMEDD(aon_regs, regs) {
regs->registerResources(*this);
SC_METHOD(clock_cb);
sensitive << clk_i;
SC_METHOD(reset_cb);
sensitive << erst_n_i;
}
void aon::start_of_simulation() {
rst_o=true;
}
void aon::clock_cb() {
this->clk = clk_i.read();
}
aon::~aon() {}
void aon::reset_cb() {
if (!erst_n_i.read()){
regs->reset_start();
rst_o=true;
} else {
regs->reset_stop();
rst_o=false;
}
lfclkc_o.write(sc_core::sc_time(1/32768., sc_core::SC_SEC));
}
void aon::reset_internal_cb() {
}
} /* namespace sysc */

124
platform/src/sysc/clint.cpp Normal file
View File

@ -0,0 +1,124 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/clint.h"
#include "scc/utilities.h"
#include "scc/report.h"
#include "sysc/SiFive/gen/clint_regs.h"
namespace sysc {
const int lfclk_mutiplier = 1 << 12;
clint::clint(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(tlclk_i)
, NAMED(lfclk_i)
, NAMED(rst_i)
, NAMED(mtime_int_o)
, NAMED(msip_int_o)
, NAMEDD(clint_regs, regs)
, cnt_fraction(0) {
regs->registerResources(*this);
SC_METHOD(clock_cb);
sensitive << tlclk_i<<lfclk_i;
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
regs->mtimecmp.set_write_cb([this](scc::sc_register<uint64_t> &reg, uint64_t data) -> bool {
if (!regs->in_reset()) {
reg.put(data);
this->update_mtime();
}
return true;
});
regs->mtime.set_read_cb([this](const scc::sc_register<uint64_t> &reg, uint64_t &data) -> bool {
this->update_mtime();
data = reg.get();
return true;
});
regs->mtime.set_write_cb([this](scc::sc_register<uint64_t> &reg, uint64_t data) -> bool { return false; });
regs->msip.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
reg.put(data);
msip_int_o.write(regs->r_msip.msip);
return true;
});
SC_METHOD(update_mtime);
sensitive << mtime_evt;
dont_initialize();
}
void clint::clock_cb() {
update_mtime();
clk = lfclk_i.read();
update_mtime();
}
clint::~clint() {}
void clint::reset_cb() {
if (rst_i.read()) {
regs->reset_start();
msip_int_o.write(false);
mtime_int_o.write(false);
cnt_fraction = 0;
} else
regs->reset_stop();
}
void clint::update_mtime() {
if(clk>SC_ZERO_TIME){
uint64_t elapsed_clks = (sc_time_stamp()-last_updt)/clk; // get the number of clock periods since last invocation
last_updt += elapsed_clks*clk; // increment the last_updt timestamp by the number of clocks
if(elapsed_clks){ // update mtime reg if we have more than 0 elapsed clk periods
regs->r_mtime+=elapsed_clks;
mtime_evt.cancel();
if (regs->r_mtimecmp > 0)
if(regs->r_mtimecmp > regs->r_mtime && clk > sc_core::SC_ZERO_TIME) {
sc_core::sc_time next_trigger = (clk * lfclk_mutiplier) * (regs->r_mtimecmp - regs->mtime) - cnt_fraction * clk;
LOG(DEBUG)<<"Timer fires at "<< sc_time_stamp()+next_trigger;
mtime_evt.notify(next_trigger);
mtime_int_o.write(false);
} else
mtime_int_o.write(true);
}
} else
last_updt = sc_time_stamp();
}
} /* namespace sysc */

View File

@ -0,0 +1,69 @@
/*
* dcmotor.cpp
*
* Created on: 25.07.2018
* Author: eyck
*/
#include "sysc/top/dcmotor.h"
#include "scc/utilities.h"
#include <future>
namespace sysc {
using namespace sc_core;
auto get_config = []() -> BLDC::Config {
BLDC::Config config{};
config.Ke=1./4000. ,//0.01; // V/rad/s, = 1/Kv
config.R=0.5; // Ohm
config.inertia = 0.0005;
config.NbPoles = 2;
config.damping = 0.00001;
return config;
};
dc_motor::dc_motor(const sc_module_name& nm )
: sc_module(nm)
, bldc_model(get_config())
, bldc_state(bldc_model.getState())
{
bldc_model.setLoad(0.0001);
SC_THREAD(thread);
}
dc_motor::~dc_motor() {
}
void dc_motor::trace(sc_trace_file* trf) {
auto ia=bldc_state.ia; TRACE_VAR(trf, ia);
auto ib=bldc_state.ib; TRACE_VAR(trf, ib);
auto ic=bldc_state.ic; TRACE_VAR(trf, ic);
auto theta=bldc_state.theta; TRACE_VAR(trf, theta);
auto omega=bldc_state.omega; TRACE_VAR(trf, omega);
}
void dc_motor::thread(void) {
wait(SC_ZERO_TIME);
std::array<double, 3> vin{0., 0., 0.};
const sc_time step(1, SC_US);
auto eval_model = [this](std::array<double, 3> vin, const sc_time step)->std::tuple<double, double, double> {
bldc_model.set_input(vin);
bldc_model.run(step.to_seconds());
return bldc_model.get_voltages();
};
while(true){
vin[0]=va_i.read();
vin[1]=vb_i.read();
vin[2]=vc_i.read();
// auto sim_res=std::async(std::launch::async, eval_model, vin, step);
wait(step);
// auto vout=sim_res.get();
auto vout = eval_model(vin, step);
va_o=std::get<0>(vout);
vb_o=std::get<1>(vout);
vc_o=std::get<2>(vout);
}
}
} /* namespace sysc */

247
platform/src/sysc/gpio.cpp Normal file
View File

@ -0,0 +1,247 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/gpio.h"
#include "sysc/sc_comm_singleton.h"
#include "scc/report.h"
#include "scc/utilities.h"
#include "sysc/SiFive/gen/gpio_regs.h"
namespace sysc {
gpio::gpio(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(clk_i)
, NAMED(rst_i)
, NAMED(pins_o, 32)
, NAMED(pins_i, 32)
, NAMED(iof0_o, 32)
, NAMED(iof1_o, 32)
, NAMED(iof0_i, 32)
, NAMED(iof1_i, 32)
, NAMEDD(gpio_regs, regs)
, NAMED(write_to_ws, false){
regs->registerResources(*this);
SC_METHOD(clock_cb);
sensitive << clk_i;
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
auto pins_i_cb =[this](unsigned int tag, tlm::tlm_signal_gp<sc_logic>& gp,
tlm::tlm_phase& phase, sc_core::sc_time& delay)->tlm::tlm_sync_enum{
this->pin_input(tag, gp, delay);
return tlm::TLM_COMPLETED;
};
auto i=0U;
for(auto& s:pins_i){
s.register_nb_transport(pins_i_cb, i);
++i;
}
auto iof0_i_cb =[this](unsigned int tag, tlm::tlm_signal_gp<bool>& gp,
tlm::tlm_phase& phase, sc_core::sc_time& delay)->tlm::tlm_sync_enum{
last_iof0[tag]=gp.get_value();
this->iof_input(tag, 0, gp, delay);
return tlm::TLM_COMPLETED;
};
i=0;
for(auto& s:iof0_i){
s.register_nb_transport(iof0_i_cb, i);
++i;
}
auto iof1_i_cb =[this](unsigned int tag, tlm::tlm_signal_gp<bool>& gp,
tlm::tlm_phase& phase, sc_core::sc_time& delay)->tlm::tlm_sync_enum{
last_iof1[tag]=gp.get_value();
this->iof_input(tag, 1, gp, delay);
return tlm::TLM_COMPLETED;
};
i=0;
for(auto& s:iof1_i){
s.register_nb_transport(iof1_i_cb, i);
++i;
}
regs->port.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
if (!this->regs->in_reset()) {
reg.put(data);
// read r_ports and update pins_io
update_pins();
}
return true;
});
regs->iof_en.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
if (!this->regs->in_reset()) {
enable_outputs(data, regs->r_iof_sel);
reg.put(data);
}
return true;
});
regs->iof_sel.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
if (!this->regs->in_reset()) {
enable_outputs(regs->r_iof_en, data);
reg.put(data);
}
return true;
});
}
gpio::~gpio() {}
void gpio::before_end_of_elaboration() {
if(write_to_ws.get_value()) {
LOG(TRACE)<<"Adding WS handler for "<<(std::string{"/ws/"}+name());
handler=std::make_shared<WsHandler>();
sc_comm_singleton::inst().registerWebSocketHandler((std::string{"/ws/"}+name()).c_str(), handler);
}
}
void gpio::reset_cb() {
if (rst_i.read())
regs->reset_start();
else
regs->reset_stop();
}
void gpio::clock_cb() {
this->clk = clk_i.read();
}
tlm::tlm_phase gpio::write_output(tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, size_t i, sc_dt::sc_logic val) {
sc_core::sc_time delay{SC_ZERO_TIME};
tlm::tlm_phase phase{ tlm::BEGIN_REQ };
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_response_status(tlm::TLM_OK_RESPONSE);
gp.set_value(val);
pins_o.at(i)->nb_transport_fw(gp, phase, delay);
return phase;
}
void gpio::update_pins() {
sc_core::sc_inout_rv<32>::data_type out_val;
tlm::tlm_signal_gp<sc_dt::sc_logic> gp;
for(size_t i=0, mask = 1; i<32; ++i, mask<<=1){
if((regs->iof_en&mask == 0) || (iof0_i[i].size()==0 && iof1_i[i].size()==0)){
auto val = regs->r_output_en&mask?
regs->r_port&mask?
sc_dt::Log_1:
sc_dt::Log_0:
sc_dt::Log_Z;
tlm::tlm_phase phase = write_output(gp, i, val);
}
}
}
void gpio::enable_outputs(uint32_t new_iof_en, uint32_t new_iof_sel) {
auto changed_bits = (regs->r_iof_en^new_iof_en) | (regs->r_iof_sel^new_iof_sel);
tlm::tlm_signal_gp<sc_dt::sc_logic> gp;
for(size_t i=0, mask=1; i<32; ++i, mask<<=1){
if(changed_bits&mask){
if(new_iof_en&mask){
if((regs->r_iof_sel&mask)==0 && iof0_i[i].size()>0){
tlm::tlm_phase phase = write_output(gp, i, last_iof0[i]?sc_dt::Log_1:sc_dt::Log_0);
} else if((regs->r_iof_sel&mask)==1 && iof1_i[i].size()>0)
tlm::tlm_phase phase = write_output(gp, i, last_iof1[i]?sc_dt::Log_1:sc_dt::Log_0);
} else {
auto val = regs->r_output_en&mask?
regs->r_port&mask?sc_dt::Log_1:sc_dt::Log_0:
sc_dt::Log_Z;
tlm::tlm_phase phase = write_output(gp, i, val);
}
}
}
}
void gpio::pin_input(unsigned int tag, tlm::tlm_signal_gp<sc_logic>& gp, sc_core::sc_time& delay) {
if(delay>SC_ZERO_TIME){
wait(delay);
delay=SC_ZERO_TIME;
}
switch(gp.get_value().value()){
case sc_dt::Log_1:
regs->r_value|=1<<tag;
forward_pin_input(tag, gp);
break;
case sc_dt::Log_0:
regs->r_value&=~(1<<tag);
forward_pin_input(tag, gp);
break;
}
}
void gpio::forward_pin_input(unsigned int tag, tlm::tlm_signal_gp<sc_logic>& gp) {
const auto mask = 1U<<tag;
if(regs->iof_en&mask){
auto& socket = regs->iof_sel&mask?iof1_o[tag]:iof0_o[tag];
tlm::tlm_signal_gp<> new_gp;
for(size_t i=0; i<socket.size(); ++i){
sc_core::sc_time delay{SC_ZERO_TIME};
tlm::tlm_phase phase{tlm::BEGIN_REQ};
new_gp.set_command(tlm::TLM_WRITE_COMMAND);
new_gp.set_response_status(tlm::TLM_OK_RESPONSE);
new_gp.set_value(gp.get_value().value()==sc_dt::Log_1);
new_gp.update_extensions_from(gp);
socket->nb_transport_fw(new_gp, phase, delay); // we don't care about phase and sync enum
}
}
}
void gpio::iof_input(unsigned int tag, unsigned iof_idx, tlm::tlm_signal_gp<>& gp, sc_core::sc_time& delay) {
if(delay>SC_ZERO_TIME){
wait(delay);
delay=SC_ZERO_TIME;
}
const auto mask = 1U<<tag;
if(regs->r_iof_en&mask){
const auto idx = regs->r_iof_sel&mask?1:0;
if(iof_idx == idx){
auto& socket = pins_o[tag];
for(size_t i=0; i<socket.size(); ++i){
sc_core::sc_time delay{SC_ZERO_TIME};
tlm::tlm_phase phase{tlm::BEGIN_REQ};
tlm::tlm_signal_gp<sc_logic> new_gp;
new_gp.set_command(tlm::TLM_WRITE_COMMAND);
auto val = gp.get_value();
new_gp.set_value(val?sc_dt::Log_1:sc_dt::Log_0);
new_gp.copy_extensions_from(gp);
socket->nb_transport_fw(new_gp, phase, delay); // we don't care about phase and sync enum
gp.update_extensions_from(new_gp);
}
}
}
}
} /* namespace sysc */

View File

@ -0,0 +1,47 @@
/*
* h_bridge.cpp
*
* Created on: 25.07.2018
* Author: eyck
*/
#include "sysc/top/h_bridge.h"
#include "scc/utilities.h"
namespace sysc {
using namespace sc_core;
h_bridge::h_bridge(const sc_module_name& nm)
:sc_module(nm)
, NAMED(ha_i)
, NAMED(la_i)
, NAMED(hb_i)
, NAMED(lb_i)
, NAMED(hc_i)
, NAMED(lc_i)
, NAMED(va_o)
, NAMED(vb_o)
, NAMED(vc_o)
, NAMED(vcc, 48.0)
{
SC_METHOD(ain_cb);
sensitive<<ha_i<<la_i;
SC_METHOD(bin_cb);
sensitive<<hb_i<<lb_i;
SC_METHOD(cin_cb);
sensitive<<hc_i<<lc_i;
}
h_bridge::~h_bridge() {
}
void h_bridge::ain_cb() {
}
void h_bridge::bin_cb() {
}
void h_bridge::cin_cb() {
}
} /* namespace sysc */

View File

@ -0,0 +1,145 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/hifive1.h"
namespace sysc {
hifive1::hifive1(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, NAMED(pins_o, 32)
, NAMED(pins_i, 32)
, NAMED(erst_n)
, NAMED(i_core_complex)
, NAMED(i_router, 12, 1)
, NAMED(i_uart0)
, NAMED(i_uart1)
, NAMED(i_qspi0)
, NAMED(i_qspi1)
, NAMED(i_qspi2)
, NAMED(i_gpio0)
, NAMED(i_plic)
, NAMED(i_aon)
, NAMED(i_prci)
, NAMED(i_clint)
, NAMED(i_mem_qspi)
, NAMED(i_mem_ram)
, NAMED(s_tlclk)
, NAMED(s_rst)
, NAMED(s_global_int, 256)
, NAMED(s_local_int, 16)
, NAMED(s_core_int)
, NAMED(s_dummy, 16)
, NAMED(s_dummy_sck_i, 16)
, NAMED(s_dummy_sck_o, 16)
{
i_core_complex.initiator(i_router.target[0]);
size_t i = 0;
for (const auto &e : e300_plat_map) {
i_router.initiator.at(i)(e.target->socket);
i_router.add_target_range(i, e.start, e.size);
i++;
}
i_router.initiator.at(i)(i_mem_qspi.target);
i_router.add_target_range(i, 0x20000000, 512_MB);
i_router.initiator.at(++i)(i_mem_ram.target);
i_router.add_target_range(i, 0x80000000, 128_kB);
i_uart0.clk_i(s_tlclk);
i_uart1.clk_i(s_tlclk);
i_qspi0.clk_i(s_tlclk);
i_qspi1.clk_i(s_tlclk);
i_qspi2.clk_i(s_tlclk);
i_gpio0.clk_i(s_tlclk);
i_plic.clk_i(s_tlclk);
i_aon.clk_i(s_tlclk);
i_aon.lfclkc_o(s_lfclk);
i_prci.hfclk_o(s_tlclk); // clock driver
i_clint.tlclk_i(s_tlclk);
i_clint.lfclk_i(s_lfclk);
i_core_complex.clk_i(s_tlclk);
i_uart0.rst_i(s_rst);
i_uart1.rst_i(s_rst);
i_qspi0.rst_i(s_rst);
i_qspi1.rst_i(s_rst);
i_qspi2.rst_i(s_rst);
i_gpio0.rst_i(s_rst);
i_plic.rst_i(s_rst);
i_aon.rst_o(s_rst);
i_prci.rst_i(s_rst);
i_clint.rst_i(s_rst);
i_core_complex.rst_i(s_rst);
i_aon.erst_n_i(erst_n);
i_clint.mtime_int_o(s_mtime_int);
i_clint.msip_int_o(s_msie_int);
i_plic.global_interrupts_i(s_global_int);
i_plic.core_interrupt_o(s_core_int);
i_core_complex.sw_irq_i(s_msie_int);
i_core_complex.timer_irq_i(s_mtime_int);
i_core_complex.global_irq_i(s_core_int);
i_core_complex.local_irq_i(s_local_int);
pins_i(i_gpio0.pins_i);
i_gpio0.pins_o(pins_o);
i_gpio0.iof0_i[17](i_uart0.tx_o);
i_uart0.rx_i(i_gpio0.iof0_o[16]);
i_uart0.irq_o(s_global_int[3]);
i_gpio0.iof0_i[2](i_qspi1.scs_o[0]);
i_gpio0.iof0_i[3](i_qspi1.mosi_o);
i_qspi1.miso_i(i_gpio0.iof0_o[4]);
i_gpio0.iof0_i[5](i_qspi1.sck_o);
i_gpio0.iof0_i[9](i_qspi1.scs_o[2]);
i_gpio0.iof0_i[10](i_qspi1.scs_o[3]);
i_qspi0.irq_o(s_global_int[5]);
i_qspi1.irq_o(s_global_int[6]);
i_qspi2.irq_o(s_global_int[7]);
s_dummy_sck_i[0](i_uart1.tx_o);
i_uart1.rx_i(s_dummy_sck_o[0]);
i_uart1.irq_o(s_global_int[4]);
for(auto& sock:s_dummy_sck_i) sock.error_if_no_callback=false;
}
} /* namespace sysc */

View File

@ -0,0 +1,86 @@
/*
* mcp3008.cpp
*
* Created on: 17.07.2018
* Author: eyck
*/
#include "sysc/top/mcp3008.h"
#include <scc/report.h>
#include <util/ities.h>
namespace sysc {
mcp3008::mcp3008(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, NAMED(sck_i)
, NAMED(miso_o)
, NAMED(mosi_i)
, NAMED(cs_i)
, NAMED(vref_i)
, NAMED(ch_i, 8)
, last_tx_start(sc_core::SC_ZERO_TIME)
{
sck_i.register_nb_transport([this](tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, tlm::tlm_phase& phase, sc_core::sc_time& delay)
-> tlm::tlm_sync_enum{
return tlm::TLM_COMPLETED;
});
mosi_i.register_nb_transport([this](tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, tlm::tlm_phase& phase, sc_core::sc_time& delay)
-> tlm::tlm_sync_enum{
if(cs_v==sc_dt::Log_0)
return receive(gp, phase, delay);
});
cs_i.register_nb_transport([this](tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, tlm::tlm_phase& phase, sc_core::sc_time& delay)
-> tlm::tlm_sync_enum{
if(cs_v!=sc_dt::Log_0 && gp.get_value()==sc_dt::Log_0){
idx=0; // falling edge
rx_bits=0;
}
cs_v=gp.get_value();
return tlm::TLM_COMPLETED;
});
}
mcp3008::~mcp3008() {
}
tlm::tlm_sync_enum mcp3008::receive(tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, tlm::tlm_phase& phase, sc_core::sc_time& delay) {
gp.get_extension(ext);
if(ext){
if( ext->start_time!=last_tx_start){
assert(ext->tx.data_bits==8);
rx_bytes[idx]=bit_sub<0,8>(ext->tx.m2s_data);
if(idx==1)
do_conversion();
ext->tx.s2m_data=tx_bytes[idx];
ext->tx.s2m_data_valid=true;
idx++;
last_tx_start=ext->start_time;
}
}
return tlm::TLM_COMPLETED;
}
void mcp3008::do_conversion() {
if(rx_bytes[0]==0x1){
auto mode = bit_sub<7,1>(rx_bytes[1]);
auto channel = bit_sub<4,3>(rx_bytes[1]);
auto vref=vref_i.read();
if(mode){ // single ended
auto inp = ch_i[channel].read();
auto norm = inp/vref*1024.0;
auto res = static_cast<int>(norm);
CLOG(DEBUG, SystemC)<<"Converting "<<inp<<" to "<<norm<<" as int "<<res;
tx_bytes[1]=bit_sub<8,2>(res);
tx_bytes[2]=bit_sub<0,8>(res);
} else {
tx_bytes[1]=0;
tx_bytes[2]=0;
}
}
}
} /* namespace sysc */

181
platform/src/sysc/plic.cpp Normal file
View File

@ -0,0 +1,181 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include <sysc/SiFive/plic.h>
#include <scc/utilities.h>
#include <scc/report.h>
#include <sysc/SiFive/gen/plic_regs.h>
namespace sysc {
plic::plic(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(clk_i)
, NAMED(rst_i)
, NAMED(global_interrupts_i, 256)
, NAMED(core_interrupt_o)
, NAMEDD(plic_regs, regs)
{
regs->registerResources(*this);
// register callbacks
init_callbacks();
regs->claim_complete.set_write_cb(m_claim_complete_write_cb);
// port callbacks
SC_METHOD(global_int_port_cb);
for (uint8_t i = 0; i < 255; i++) {
sensitive << global_interrupts_i[i].pos();
}
dont_initialize();
// register event callbacks
SC_METHOD(clock_cb);
sensitive << clk_i;
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
}
plic::~plic() {}
void plic::init_callbacks() {
m_claim_complete_write_cb = [=](scc::sc_register<uint32_t> reg, uint32_t v) -> bool {
reg.put(v);
reset_pending_int(v);
// std::cout << "Value of register: 0x" << std::hex << reg << std::endl;
// todo: reset related interrupt and find next high-prio interrupt
return true;
};
}
void plic::clock_cb() {
this->clk = clk_i.read();
}
void plic::reset_cb() {
if (rst_i.read())
regs->reset_start();
else
regs->reset_stop();
}
// Functional handling of interrupts:
// - global_int_port_cb()
// - set pending register bits
// - called by: incoming global_int
// - handle_pending_int()
// - update claim register content
// - generate core-interrupt pulse
// - called by:
// - incoming global_int
// - complete-register write access
// - reset_pending_int(int-id)
// - reset pending bit
// - call next handle_pending_int()
// - called by:
// - complete-reg write register content
void plic::global_int_port_cb() {
// set related pending bit if enable is set for incoming global_interrupt
for (uint32_t i = 1; i < 256; i++) {
auto reg_idx = i>>5;
auto bit_ofs = i & 0x1F;
bool enable = regs->r_enabled[reg_idx] & (0x1 << bit_ofs); // read enable bit
if (enable && global_interrupts_i[i].read() == 1) {
regs->r_pending[reg_idx] = regs->r_pending[reg_idx] | (0x1 << bit_ofs);
LOG(DEBUG) << "pending interrupt identified: " << i;
}
}
handle_pending_int();
}
void plic::handle_pending_int() {
// identify high-prio pending interrupt and raise a core-interrupt
uint32_t claim_int = 0; // claim interrupt
uint32_t claim_prio = 0; // related priority (highest prio interrupt wins the race)
bool raise_int = 0;
uint32_t thold = regs->r_threshold.threshold; // threshold value
for (uint32_t i = 1; i < 255; i++) {
auto reg_idx = i>>5;
auto bit_ofs = i & 0x1F;
bool pending = (regs->r_pending[reg_idx] & (0x1 << bit_ofs)) ? true : false;
uint32_t prio = regs->r_priority[i - 1].priority; // read priority value
if (pending && thold < prio) {
regs->r_pending[reg_idx] = regs->r_pending[reg_idx] | (0x1 << bit_ofs);
// below condition ensures implicitly that lowest id is selected in case of multiple identical
// priority-interrupts
if (prio > claim_prio) {
claim_prio = prio;
claim_int = i;
raise_int = 1;
LOG(DEBUG) << "pending interrupt activated: " << i;
}
}
}
if (raise_int) {
regs->r_claim_complete = claim_int;
core_interrupt_o.write(1);
// todo: evluate clock period
} else {
regs->r_claim_complete = 0;
LOG(DEBUG) << "no further pending interrupt.";
}
}
void plic::reset_pending_int(uint32_t irq) {
// todo: evaluate enable register (see spec)
// todo: make sure that pending is set, otherwise don't reset irq ... read spec.
LOG(TRACE) << "reset pending interrupt: " << irq;
// reset related pending bit
auto reg_idx = irq>>5;
auto bit_ofs = irq & 0x1F;
regs->r_pending[reg_idx] &= ~(0x1 << bit_ofs);
core_interrupt_o.write(0);
// evaluate next pending interrupt
handle_pending_int();
}
} /* namespace sysc */

145
platform/src/sysc/prci.cpp Normal file
View File

@ -0,0 +1,145 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/prci.h"
#include "scc/utilities.h"
#include "sysc/SiFive/gen/prci_regs.h"
namespace sysc {
prci::prci(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(hfclk)
, NAMED(rst_i)
, NAMED(hfclk_o)
, NAMEDD(prci_regs, regs) {
regs->registerResources(*this);
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
SC_METHOD(hfxosc_cb);
sensitive << hfxosc_i;
SC_METHOD(hfrosc_en_cb);
sensitive << hfrosc_en_evt;
dont_initialize();
regs->hfxosccfg.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
reg.put(data);
if (this->regs->r_hfxosccfg.hfxoscen==1) { // check rosc_en
this->hfxosc_en_evt.notify(1, sc_core::SC_US);
} else {
this->hfxosc_en_evt.notify(SC_ZERO_TIME);
}
return true;
});
regs->hfrosccfg.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
reg.put(data);
if (this->regs->r_hfrosccfg.hfroscen==1) { // check rosc_en
this->hfrosc_en_evt.notify(1, sc_core::SC_US);
} else {
this->hfrosc_en_evt.notify(SC_ZERO_TIME);
}
return true;
});
regs->pllcfg.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
reg.put(data);
auto &pllcfg = this->regs->r_pllcfg;
if (pllcfg.pllbypass == 0 && pllcfg.pllq != 0) { // set pll_lock if pll is selected
pllcfg.plllock = 1;
}
update_hfclk();
return true;
});
regs->plloutdiv.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
reg.put(data);
update_hfclk();
return true;
});
hfxosc_clk=62.5_ns;
}
prci::~prci() {}
void prci::reset_cb() {
if (rst_i.read())
regs->reset_start();
else {
regs->reset_stop();
this->hfxosc_en_evt.notify(1, sc_core::SC_US);
}
}
void prci::hfxosc_cb() {
this->regs->r_hfxosccfg.hfxoscrdy=0;
this->hfxosc_en_evt.notify(1, sc_core::SC_US);
}
void prci::hfxosc_en_cb() {
update_hfclk();
if(regs->r_hfxosccfg.hfxoscen==1)// set rosc_rdy
regs->r_hfxosccfg.hfxoscrdy =1;
else
regs->r_hfxosccfg.hfxoscrdy =0;
}
void prci::hfrosc_en_cb() {
update_hfclk();
auto& hfrosccfg=regs->r_hfrosccfg;
if(regs->r_hfrosccfg.hfroscen==1) {// set rosc_rdy
regs->r_hfrosccfg.hfroscrdy =1;
} else {
regs->r_hfrosccfg.hfroscrdy =0;
}
}
void prci::update_hfclk() {
auto& hfrosccfg=regs->r_hfrosccfg;
auto& pllcfg=regs->r_pllcfg;
auto& plldiv=regs->r_plloutdiv;
hfrosc_clk = sc_core::sc_time(((hfrosccfg.hfroscdiv+1)*1.0)/(1125000.0*(hfrosccfg.hfrosctrim+1)), sc_core::SC_SEC);
auto pll_ref = pllcfg.pllrefsel==1?hfxosc_clk:hfrosc_clk;
auto r = pllcfg.pllr+1;
auto f = 2*(pllcfg.pllf+1);
auto q = 1<<pllcfg.pllq;
auto pll_out = pllcfg.pllbypass==1 || pllcfg.plllock==0?pll_ref:((pll_ref*r)/f)*q;
auto pll_res = plldiv&0x100?pll_out:2*pll_out*((plldiv&0x3f)+1);
hfclk = pllcfg.pllsel?pll_res:hfrosc_clk;
hfclk_o.write(hfclk);
}
} /* namespace sysc */

View File

@ -0,0 +1,184 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/sc_comm_singleton.h"
#include "seasocks/PrintfLogger.h"
#include "seasocks/Server.h"
#include "seasocks/StringUtil.h"
#include "seasocks/util/Json.h"
#include "seasocks/ResponseWriter.h"
#include "seasocks/util/RootPageHandler.h"
#include "seasocks/util/CrackedUriPageHandler.h"
#include "seasocks/util/StaticResponseHandler.h"
#include <cstdio>
#include <csignal>
#include <sys/stat.h>
#include <cerrno>
#include <fcntl.h>
#include <unistd.h>
namespace sysc {
using namespace seasocks;
using namespace std;
namespace {
inline void die(){perror(nullptr);exit(errno);}
}
sc_comm_singleton::sc_comm_singleton(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, m_serv(new Server(std::make_shared<PrintfLogger>(Logger::Level::WARNING)))
, needs_client(false)
, client_started(false){
m_serv->addPageHandler(std::make_shared<DefaultPageHandler>(*this));
}
sc_comm_singleton::~sc_comm_singleton() {
//Join the thread with the main thread
t.join();
}
void sc_comm_singleton::start_of_simulation() {
//Launch a thread
t=std::thread(&sc_comm_singleton::thread_func, this);
if(needs_client) start_client();
}
void sc_comm_singleton::end_of_simulation() {
get_server().terminate();
}
void sc_comm_singleton::start_client() {
if(client_started) return;
std::stringstream ss;
#ifndef WIN32
if(fork()==0){
// daemonizing, see http://www.microhowto.info/howto/cause_a_process_to_become_a_daemon_in_c.html#id2407077
// Fork, allowing the parent process to terminate.
pid_t pid = fork();
if (pid == -1) {
die();
} else if (pid != 0) {
_exit(0);
}
// Start a new session for the daemon.
if (setsid()==-1) die();
// Fork again, allowing the parent process to terminate.
signal(SIGHUP,SIG_IGN);
pid=fork();
if (pid == -1) {
die();
} else if (pid != 0) {
_exit(0);
}
// Set the current working directory to the root directory.
if (chdir("/") == -1) die();
// Set the user file creation mask to zero.
umask(0);
// Close then reopen standard file descriptors.
close(STDIN_FILENO);
close(STDOUT_FILENO);
close(STDERR_FILENO);
if (open("/dev/null",O_RDONLY) == -1) die();
if (open("/dev/null",O_WRONLY) == -1) die();
if (open("/dev/null",O_RDWR) == -1) die();
// now do what is needed
ss<<"x-www-browser http://localhost:9090/ws.html"; //Linux
auto res = system (ss.str().c_str());
if(res==0) exit(0);
ss.str("");
ss<<"xdg-open http://localhost:9090/ws.html"; // Linux
res=system (ss.str().c_str());
if(res==0) exit(0);
ss.str("");
ss<<"open http://localhost:9090/ws.html"; // MacOS
res=system (ss.str().c_str());
exit(0);
}
// #else
// on windows should be open, see https://www.experts-exchange.com/articles/1595/Execute-a-Program-with-C.html
#endif
client_started=true;
}
void sc_comm_singleton::registerWebSocketHandler(const char* endpoint,
std::shared_ptr<WebSocket::Handler> handler,
bool allowCrossOriginRequests) {
get_server().addWebSocketHandler(endpoint, handler, allowCrossOriginRequests);
endpoints.push_back(endpoint);
needs_client=true;
}
void sc_comm_singleton::execute(std::function<void()> f) {
get_server().execute(f);
}
void sc_comm_singleton::thread_func() {
get_server().serve("./html", 9090);
}
Server& sc_comm_singleton::get_server() {
return *m_serv.get();
}
std::shared_ptr<Response> sc_comm_singleton::DefaultPageHandler::handle(const Request& request) {
if(request.verb() == Request::Verb::Get && request.getRequestUri()=="conf.json"){
return Response::htmlResponse("{}");
}
return Response::unhandled();
}
void WsHandler::onConnect(WebSocket* connection) {
_connections.insert(connection);
}
void WsHandler::onData(WebSocket* connection, const char* data) {
if (0 == strcmp("close", data)) {
connection->close();
} else if(callback)
callback(data);
}
void WsHandler::onDisconnect(WebSocket* connection) {
_connections.erase(connection);
}
} /* namespace sysc */

219
platform/src/sysc/spi.cpp Normal file
View File

@ -0,0 +1,219 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/spi.h"
#include "sysc/tlm_extensions.h"
#include "scc/utilities.h"
#include "sysc/SiFive/gen/spi_regs.h"
#include <util/ities.h>
namespace sysc {
spi::spi(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(clk_i)
, NAMED(rst_i)
, NAMED(sck_o)
, NAMED(mosi_o)
, NAMED(miso_i)
, NAMED(scs_o, 4)
, NAMED(irq_o)
, NAMED(bit_true_transfer, false)
, NAMEDD(spi_regs, regs) {
regs->registerResources(*this);
SC_METHOD(clock_cb);
sensitive << clk_i;
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
SC_THREAD(transmit_data);
miso_i.register_nb_transport([this](tlm::tlm_signal_gp<bool>& gp,
tlm::tlm_phase& phase, sc_core::sc_time& delay)->tlm::tlm_sync_enum{
this->receive_data(gp, delay);
return tlm::TLM_COMPLETED;
});
regs->txdata.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
if (!this->regs->in_reset()) {
reg.put(data);
tx_fifo.nb_write(static_cast<uint8_t>(regs->r_txdata.data));
regs->r_txdata.full=tx_fifo.num_free()==0;
update_irq();
}
return true;
});
regs->rxdata.set_read_cb([this](const scc::sc_register<uint32_t> &reg, uint32_t& data) -> bool {
if (!this->regs->in_reset()) {
uint8_t val;
if(rx_fifo.nb_read(val)){
regs->r_rxdata.empty=0;
regs->r_rxdata.data=val;
if(regs->r_rxmark.rxmark<=rx_fifo.num_available()){
regs->r_ip.rxwm=1;
update_irq();
}
} else
regs->r_rxdata.empty=1;
data = reg.get()&reg.rdmask;
}
return true;
});
regs->csmode.set_write_cb([this](const scc::sc_register<uint32_t> &reg, uint32_t& data) -> bool {
if(regs->r_csmode.mode==2 && regs->r_csmode.mode != bit_sub<0, 2>(data) && regs->r_csid<4){
tlm::tlm_phase phase(tlm::BEGIN_REQ);
sc_core::sc_time delay(SC_ZERO_TIME);
tlm::tlm_signal_gp<> gp;
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_value(true);
scs_o[regs->r_csid]->nb_transport_fw(gp, phase, delay);
}
reg.put(data);
return true;
});
regs->csid.set_write_cb([this](const scc::sc_register<uint32_t> &reg, uint32_t& data) -> bool {
if(regs->r_csmode.mode==2 && regs->csid != data && regs->r_csid<4){
tlm::tlm_phase phase(tlm::BEGIN_REQ);
sc_core::sc_time delay(SC_ZERO_TIME);
tlm::tlm_signal_gp<> gp;
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_value(true);
scs_o[regs->r_csid]->nb_transport_fw(gp, phase, delay);
}
reg.put(data);
return true;
});
regs->csdef.set_write_cb([this](const scc::sc_register<uint32_t> &reg, uint32_t& data) -> bool {
auto diff = regs->csdef ^ data;
if(regs->r_csmode.mode==2 && diff!=0 && (regs->r_csid<4) && (diff & (1<<regs->r_csid))!=0){
tlm::tlm_phase phase(tlm::BEGIN_REQ);
sc_core::sc_time delay(SC_ZERO_TIME);
tlm::tlm_signal_gp<> gp;
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_value(true);
scs_o[regs->r_csid]->nb_transport_fw(gp, phase, delay);
}
reg.put(data);
return true;
});
regs->ie.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
update_irq();
});
regs->ip.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
update_irq();
});
}
spi::~spi() {}
void spi::clock_cb() {
this->clk = clk_i.read();
}
void spi::reset_cb() {
if (rst_i.read())
regs->reset_start();
else
regs->reset_stop();
}
void spi::transmit_data() {
uint8_t txdata;
sysc::tlm_signal_spi_extension ext;
tlm::tlm_phase phase(tlm::BEGIN_REQ);
tlm::tlm_signal_gp<> gp;
sc_core::sc_time delay(SC_ZERO_TIME);
sc_core::sc_time bit_duration(SC_ZERO_TIME);
gp.set_extension(&ext);
ext.tx.data_bits=8;
auto set_bit = [&](bool val, scc::tlm_signal_bool_opt_out& socket){
if(socket.get_interface()==nullptr) return;
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_value(val);
tlm::tlm_phase phase(tlm::BEGIN_REQ);
socket->nb_transport_fw(gp, phase, delay);
};
wait(delay); //intentionally 0ns;
while(true){
wait(tx_fifo.data_written_event());
if(regs->r_csmode.mode != 3 && regs->r_csid<4) // not in OFF mode
set_bit(false, scs_o[regs->r_csid]);
set_bit(regs->r_sckmode.pol, sck_o);
while(tx_fifo.nb_read(txdata)){
regs->r_txdata.full=tx_fifo.num_free()==0;
regs->r_ip.txwm=regs->r_txmark.txmark<=(7-tx_fifo.num_free())?1:0;
bit_duration = 2*(regs->r_sckdiv.div+1)*clk;
ext.start_time = sc_core::sc_time_stamp();
ext.tx.m2s_data=txdata;
ext.tx.s2m_data_valid=false;
set_bit(txdata&0x80, mosi_o); // 8 data bits, MSB first
set_bit(1-regs->r_sckmode.pol, sck_o);
wait(bit_duration/2);
set_bit(regs->r_sckmode.pol, sck_o);
wait(bit_duration/2);
if(bit_true_transfer.get_value()){
for(size_t i = 0, mask=0x40; i<7; ++i, mask>=1){
set_bit(txdata&mask, mosi_o); // 8 data bits, MSB first
set_bit(1-regs->r_sckmode.pol, sck_o);
wait(bit_duration/2);
set_bit(regs->r_sckmode.pol, sck_o);
wait(bit_duration/2);
}
} else
wait(7*bit_duration);
rx_fifo.nb_write(ext.tx.s2m_data&0xff);
if(regs->r_rxmark.rxmark<=rx_fifo.num_available()){
regs->r_ip.rxwm=1;
update_irq();
}
}
if(regs->r_csmode.mode == 0 && regs->r_csid<4) // in AUTO mode
set_bit(false, scs_o[regs->r_csid]);
}
}
void spi::receive_data(tlm::tlm_signal_gp<>& gp, sc_core::sc_time& delay) {
}
void spi::update_irq() {
}
} /* namespace sysc */

View File

@ -0,0 +1,88 @@
/*
* system.cpp
*
* Created on: 11.07.2018
* Author: eyck
*/
#include "sysc/top/system.h"
using namespace sysc;
system::system(sc_core::sc_module_name nm)
: sc_module(nm)
, NAMED(s_gpio, 32)
, NAMED(s_rst_n)
, NAMED(s_vref)
, NAMED(s_va)
, NAMED(s_vb)
, NAMED(s_vc)
, NAMED(s_ana, 5)
, NAMED(i_platform)
, NAMED(i_terminal)
, NAMED(i_adc)
, NAMED(i_h_bridge)
, NAMED(i_motor)
{
// connect platform
i_platform.erst_n(s_rst_n);
for(auto i=0U; i<s_gpio.size(); ++i){
s_gpio[i].in(i_platform.pins_o[i]);
i_platform.pins_i[i](s_gpio[i].out);
}
// connect other units
// terminal
i_terminal.tx_o(s_gpio[16].in);
s_gpio[17].out(i_terminal.rx_i);
// adc digital io
s_gpio[2].out(i_adc.cs_i);
s_gpio[3].out(i_adc.mosi_i);
i_adc.miso_o(s_gpio[4].in);
s_gpio[5].out(i_adc.sck_i);
// adc analog inputs
i_adc.vref_i(s_vref);
i_adc.ch_i[0](s_vasens);
i_adc.ch_i[1](s_vbsens);
i_adc.ch_i[2](s_vcsens);
i_adc.ch_i[3](s_ana[0]);
i_adc.ch_i[4](s_ana[1]);
i_adc.ch_i[5](s_ana[2]);
i_adc.ch_i[6](s_ana[3]);
i_adc.ch_i[7](s_ana[4]);
i_h_bridge.ha_i(s_gpio[0]);
i_h_bridge.la_i(s_gpio[1]);
i_h_bridge.hb_i(s_gpio[10]);
i_h_bridge.lb_i(s_gpio[11]);
i_h_bridge.hc_i(s_gpio[19]);
i_h_bridge.lc_i(s_gpio[20]);
i_h_bridge.va_o(s_va);
i_h_bridge.vb_o(s_vb);
i_h_bridge.vc_o(s_vc);
i_motor.va_i(s_va);
i_motor.vb_i(s_vb);
i_motor.vc_i(s_vc);
i_motor.va_o(s_vasens);
i_motor.vb_o(s_vbsens);
i_motor.vc_o(s_vcsens);
SC_THREAD(gen_por);
}
system::~system() {
}
void sysc::system::gen_por() {
// single shot
s_rst_n = false;
wait(10_ns);
s_rst_n = true;
s_vref=1.024;
double val=0.1;
for(auto& sig:s_ana){
sig=val;
val+=0.12;
}
}

View File

@ -0,0 +1,69 @@
/*
* terminal.cpp
*
* Created on: 07.07.2018
* Author: eyck
*/
#include "sysc/top/terminal.h"
#include "sysc/sc_comm_singleton.h"
#include "sysc/tlm_extensions.h"
#include "scc/report.h"
using namespace sysc;
terminal::terminal()
: terminal(sc_core::sc_gen_unique_name("terminal"))
{
}
terminal::terminal(const sc_core::sc_module_name& nm)
: sc_core::sc_module(nm)
, NAMED(tx_o)
, NAMED(rx_i)
, NAMED(write_to_ws, false)
{
rx_i.register_nb_transport([this](
tlm::tlm_signal_gp<sc_dt::sc_logic>& gp,
tlm::tlm_phase& phase,
sc_core::sc_time& delay)->tlm::tlm_sync_enum{
this->receive(gp, delay);
return tlm::TLM_COMPLETED;
});
}
terminal::~terminal() {
}
void terminal::before_end_of_elaboration() {
if(write_to_ws.get_value()) {
LOG(TRACE)<<"Adding WS handler for "<<(std::string{"/ws/"}+name());
handler=std::make_shared<WsHandler>();
sc_comm_singleton::inst().registerWebSocketHandler((std::string{"/ws/"}+name()).c_str(), handler);
}
}
void terminal::receive(tlm::tlm_signal_gp<sc_dt::sc_logic>& gp, sc_core::sc_time& delay) {
sysc::tlm_signal_uart_extension* ext;
gp.get_extension(ext);
if(ext && ext->start_time!=last_tx_start){
uint8_t txdata = static_cast<uint8_t>(ext->tx.data);
last_tx_start = ext->start_time;
if(txdata != '\r') queue.push_back(txdata);
if (queue.size() >> 0 && (txdata == '\n' || txdata == 0)) {
std::string msg(queue.begin(), queue.end()-1);
sc_core::sc_time now = sc_core::sc_time_stamp();
if(handler)
sysc::sc_comm_singleton::inst().execute([this, msg, now](){
std::stringstream os;
os << "{\"time\":\"" << now << "\",\"message\":\""<<msg<<"\"}";
this->handler->send(os.str());
});
else
LOG(INFO) << this->name() << " receive: '" << msg << "'";
queue.clear();
}
}
}

183
platform/src/sysc/uart.cpp Normal file
View File

@ -0,0 +1,183 @@
////////////////////////////////////////////////////////////////////////////////
// Copyright (C) 2017, MINRES Technologies GmbH
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// 1. Redistributions of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// 2. Redistributions in binary form must reproduce the above copyright notice,
// this list of conditions and the following disclaimer in the documentation
// and/or other materials provided with the distribution.
//
// 3. Neither the name of the copyright holder nor the names of its contributors
// may be used to endorse or promote products derived from this software
// without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Contributors:
// eyck@minres.com - initial implementation
//
//
////////////////////////////////////////////////////////////////////////////////
#include "sysc/SiFive/uart.h"
#include "sysc/tlm_extensions.h"
#include "scc/report.h"
#include "scc/utilities.h"
#include "sysc/SiFive/gen/uart_regs.h"
using namespace std;
namespace sysc {
uart::uart(sc_core::sc_module_name nm)
: sc_core::sc_module(nm)
, tlm_target<>(clk)
, NAMED(clk_i)
, NAMED(rst_i)
, NAMED(tx_o)
, NAMED(rx_i)
, NAMED(irq_o)
, NAMED(bit_true_transfer, false)
, NAMEDD(uart_regs, regs)
, NAMED(rx_fifo, 8)
, NAMED(tx_fifo, 8)
{
regs->registerResources(*this);
SC_METHOD(clock_cb);
sensitive << clk_i;
SC_METHOD(reset_cb);
sensitive << rst_i;
dont_initialize();
SC_THREAD(transmit_data);
rx_i.register_nb_transport([this](tlm::tlm_signal_gp<bool>& gp,
tlm::tlm_phase& phase, sc_core::sc_time& delay)->tlm::tlm_sync_enum{
this->receive_data(gp, delay);
return tlm::TLM_COMPLETED;
});
regs->txdata.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
if (!this->regs->in_reset()) {
reg.put(data);
tx_fifo.nb_write(static_cast<uint8_t>(regs->r_txdata.data));
regs->r_txdata.full=tx_fifo.num_free()==0;
regs->r_ip.txwm=regs->r_txctrl.txcnt<=(7-tx_fifo.num_free())?1:0;
update_irq();
}
return true;
});
regs->rxdata.set_read_cb([this](const scc::sc_register<uint32_t> &reg, uint32_t& data) -> bool {
if (!this->regs->in_reset()) {
uint8_t val;
if(rx_fifo.nb_read(val)){
regs->r_rxdata.data=val;
if(regs->r_rxctrl.rxcnt<=rx_fifo.num_available()){
regs->r_ip.rxwm=1;
update_irq();
}
}
data = reg.get()&reg.rdmask;
}
return true;
});
regs->ie.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
update_irq();
});
regs->ip.set_write_cb([this](scc::sc_register<uint32_t> &reg, uint32_t data) -> bool {
update_irq();
});
}
uart::~uart() {}
void uart::update_irq() {
irq_o=(regs->r_ip.rxwm==1 && regs->r_ie.rxwm==1) || (regs->r_ip.txwm==1 && regs->r_ie.txwm==1);
}
void uart::clock_cb() {
this->clk = clk_i.read();
}
void uart::reset_cb() {
if (rst_i.read())
regs->reset_start();
else
regs->reset_stop();
}
void uart::transmit_data() {
uint8_t txdata;
sysc::tlm_signal_uart_extension ext;
tlm::tlm_phase phase(tlm::BEGIN_REQ);
tlm::tlm_signal_gp<> gp;
sc_core::sc_time delay(SC_ZERO_TIME);
sc_core::sc_time bit_duration(SC_ZERO_TIME);
gp.set_extension(&ext);
ext.tx.data_bits=8;
ext.tx.parity=false;
auto set_bit = [&](bool val){
gp.set_command(tlm::TLM_WRITE_COMMAND);
gp.set_value(val);
tlm::tlm_phase phase(tlm::BEGIN_REQ);
tx_o->nb_transport_fw(gp, phase, delay);
if(delay<bit_duration) wait(bit_duration-delay);
};
wait(delay);
while(true){
set_bit(true);
wait(tx_fifo.data_written_event());
while(tx_fifo.nb_read(txdata)){
regs->r_txdata.full=tx_fifo.num_free()==0;
regs->r_ip.txwm=regs->r_txctrl.txcnt<=(7-tx_fifo.num_free())?1:0;
bit_duration = (regs->r_div.div+1)*clk;
ext.start_time = sc_core::sc_time_stamp();
ext.tx.stop_bits=1+regs->r_txctrl.nstop;
ext.tx.baud_rate=static_cast<unsigned>(1/bit_duration.to_seconds());
ext.tx.data=txdata;
set_bit(false); // start bit
if(bit_true_transfer.get_value()){
for(int i = 8; i>0; --i)
set_bit(txdata&(1<<(i-1))); // 8 data bits, MSB first
if(regs->r_txctrl.nstop) set_bit(true); // stop bit 1
} else
wait(8*bit_duration);
set_bit(true); // stop bit 1/2
}
}
}
void uart::receive_data(tlm::tlm_signal_gp<>& gp, sc_core::sc_time& delay) {
sysc::tlm_signal_uart_extension* ext{nullptr};
gp.get_extension(ext);
if(ext && ext->start_time != rx_last_start){
auto data = static_cast<uint8_t>(ext->tx.data);
if(ext->tx.parity || ext->tx.data_bits!=8) data = rand(); // random value if wrong config
rx_fifo.write(data);
if(regs->r_rxctrl.rxcnt<=rx_fifo.num_available()){
regs->r_ip.rxwm=1;
update_irq();
}
rx_last_start=ext->start_time; // omit repeated handling of signal changes
}
gp.set_response_status(tlm::TLM_OK_RESPONSE);
}
} /* namespace sysc */