Skip to content

Commit

Permalink
Pass Modbus RTS settings through new hardware layer settings struct
Browse files Browse the repository at this point in the history
  • Loading branch information
Chrismettal committed Mar 17, 2024
1 parent efad7ba commit d38100e
Show file tree
Hide file tree
Showing 19 changed files with 45 additions and 24 deletions.
2 changes: 2 additions & 0 deletions webserver/core/custom_layer.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
// in here by clicking on the "Restore Original Code" button above.
//-----------------------------------------------------------------------------

#include "custom_layer_options.h"

//-----------------------------------------------------------------------------
// These are the ignored I/O vectors. If you want to override how OpenPLC
// handles a particular input or output, you must put them in the ignored
Expand Down
11 changes: 11 additions & 0 deletions webserver/core/custom_layer_options.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
//-----------------------------------------------------------------------------
// DISCLAIMER: EDDITING THIS FILE CAN BREAK YOUR OPENPLC RUNTIME! IF YOU DON'T
// KNOW WHAT YOU'RE DOING, JUST DON'T DO IT. EDIT AT YOUR OWN RISK.
//
// PS: You can always restore original functionality if you broke something
// in here by clicking on the "Restore Original Code" button above.
//-----------------------------------------------------------------------------

struct custom_layer_options {
uint8_t rpi_modbus_rts_pin; // If <> 0, expect hardware RTS to be used with this pin
};
7 changes: 4 additions & 3 deletions webserver/core/hardware_layers/PiPLC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ int analogOutBufferPinMask[MAX_ANALOG_OUT] = { 1, 24 };
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
wiringPiSetup();
//piHiPri(99);
Expand Down Expand Up @@ -108,9 +108,10 @@ void initializeHardware()
pinMode(analogOutBufferPinMask[i], PWM_OUTPUT);
}

// I²C?
// Modbus
customLayerOptions.rpi_modbus_rts_pin = MODBUS_RTS;

// Modbus?
// I²C?

// 1-Wire?
}
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/blank.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
}

Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/fischertechnik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ int serialFd; //serial file descriptor
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
wiringPiSetup();
//piHiPri(99);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/neuron.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,7 +264,7 @@ void searchForIO()
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
searchForIO();
}
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/pixtend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -813,7 +813,7 @@ void *updateLocalBuffers(void *args)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
Spi_Setup(0);
Spi_Setup(1);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/pixtend2l.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -596,7 +596,7 @@ void *updateLocalBuffers(void *args)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
Spi_SetupV2(0);
Spi_SetupV2(1);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/pixtend2s.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -533,7 +533,7 @@ void *updateLocalBuffers(void *args)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
Spi_SetupV2(0);
Spi_SetupV2(1);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/psm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,7 @@ void kill_psm()
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
//Verify if there is any old PSM running on the background and kill it
if ((psm = connect_to_psm(0)) >= 0)
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/raspberrypi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ int analogOutBufferPinMask[MAX_ANALOG_OUT] = { 18 };
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
gpioInitialise();
//piHiPri(99);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/raspberrypi_old.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ int analogOutBufferPinMask[MAX_ANALOG_OUT] = { 1 };
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
wiringPiSetup();
//piHiPri(99);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/sequent.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1665,7 +1665,7 @@ int mosfets8Set(uint8_t stack, uint8_t val)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
}

Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/simulink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ void *exchangeData(void *arg)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
pthread_t thread;
pthread_create(&thread, NULL, exchangeData, NULL);
Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/sl_rp4.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ int16_t getSwitchId()
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
}

Expand Down
2 changes: 1 addition & 1 deletion webserver/core/hardware_layers/unipi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ int mcp_adcRead(int chan)
// This function is called by the main OpenPLC routine when it is initializing.
// Hardware initialization procedures should be here.
//-----------------------------------------------------------------------------
void initializeHardware()
void initializeHardware(custom_layer_options& customLayerOptions)
{
wiringPiSetup();
mcp_adcSetup(0x68); //ADC I2C address configuration
Expand Down
4 changes: 2 additions & 2 deletions webserver/core/ladder.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ void glueVars();
void updateTime();

//hardware_layer.cpp
void initializeHardware();
void initializeHardware(custom_layer_options& customLayerOptions);
void finalizeHardware();
void updateBuffersIn();
void updateBuffersOut();
Expand Down Expand Up @@ -155,7 +155,7 @@ int processEnipMessage(unsigned char *buffer, int buffer_size);
uint16_t processPCCCMessage(unsigned char *buffer, int buffer_size);

//modbus_master.cpp
void initializeMB();
void initializeMB(custom_layer_options& customLayerOptions);
void *querySlaveDevices(void *arg);
void updateBuffersIn_MB();
void updateBuffersOut_MB();
Expand Down
8 changes: 6 additions & 2 deletions webserver/core/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include "iec_types.h"
#include "ladder.h"
#include "custom_layer_options.h"
#ifdef _ethercat_src
#include "ethercat_src.h"
#endif
Expand Down Expand Up @@ -264,8 +265,11 @@ int main(int argc,char **argv)
type_logger_callback logger = logger_callback;
ethercat_configure("../utils/ethercat_src/build/ethercat.cfg", logger);
#endif
initializeHardware();
initializeMB();
// Create layer options struct to pass settings between hardware layers and other init methods
custom_layer_options customLayerOptions;

initializeHardware(customLayerOptions);
initializeMB(customLayerOptions);
initCustomLayer();
updateBuffersIn();
updateCustomIn();
Expand Down
11 changes: 7 additions & 4 deletions webserver/core/modbus_master.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -610,7 +610,7 @@ void *querySlaveDevices(void *arg)
// This function is called by the main OpenPLC routine when it is initializing.
// Modbus master initialization procedures are here.
//-----------------------------------------------------------------------------
void initializeMB()
void initializeMB(custom_layer_options& customLayerOptions)
{
parseConfig();

Expand Down Expand Up @@ -649,9 +649,12 @@ void initializeMB()
mb_devices[i].rtu_parity, mb_devices[i].rtu_data_bit,
mb_devices[i].rtu_stop_bit);

modbus_enable_rpi(mb_devices[i].mb_ctx,TRUE);
modbus_configure_rpi_bcm_pin(mb_devices[i].mb_ctx,6);
modbus_rpi_pin_export_direction(mb_devices[i].mb_ctx);
// If hardware layer set modbus_rts_pin, enable Pi specific rts handling handling
if (customLayerOptions.rpi_modbus_rts_pin != 0) {
modbus_enable_rpi(mb_devices[i].mb_ctx,TRUE);
modbus_configure_rpi_bcm_pin(mb_devices[i].mb_ctx,customLayerOptions.rpi_modbus_rts_pin;
modbus_rpi_pin_export_direction(mb_devices[i].mb_ctx);
}
}
}

Expand Down

0 comments on commit d38100e

Please sign in to comment.