From 966f33dafdb7769232fbc5f133a71a7231ef2f93 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Mon, 10 Jul 2023 17:24:58 +0200 Subject: [PATCH 01/47] AnalogIn class refactoring --- .../Analog_input_0_10V/Analog_input_0_10V.ino | 12 +- .../Analog_input_4_20mA.ino | 12 +- .../Analog_input_NTC/Analog_input_NTC.ino | 12 +- src/AnalogInClass.cpp | 144 ++++++++++++++++++ src/AnalogInClass.h | 66 ++++++++ src/Arduino_MachineControl.h | 133 +--------------- src/Objects.cpp | 1 - 7 files changed, 224 insertions(+), 156 deletions(-) create mode 100644 src/AnalogInClass.cpp create mode 100644 src/AnalogInClass.h diff --git a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino index 9305875..4c1b9bf 100644 --- a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino +++ b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino @@ -17,32 +17,28 @@ */ #include -using namespace machinecontrol; - float res_divider = 0.28057; float reference = 3.3; void setup() { - analogReadResolution(16); - Serial.begin(9600); - analog_in.set0_10V(); + MachineControl_AnalogIn.begin(MCAI_SENSOR_0_10V); } void loop() { - float raw_voltage_ch0 = analog_in.read(0); + float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535 / res_divider; Serial.print("Voltage CH0: "); Serial.print(voltage_ch0, 3); Serial.println("V"); - float raw_voltage_ch1 = analog_in.read(1); + float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535 / res_divider; Serial.print("Voltage CH1: "); Serial.print(voltage_ch1, 3); Serial.println("V"); - float raw_voltage_ch2 = analog_in.read(2); + float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535 / res_divider; Serial.print("Voltage CH2: "); Serial.print(voltage_ch2, 3); diff --git a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino index 167de2d..e6fff35 100644 --- a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino +++ b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino @@ -17,34 +17,30 @@ */ #include -using namespace machinecontrol; - #define SENSE_RES 120 float reference = 3.3; void setup() { - analogReadResolution(16); - Serial.begin(9600); - analog_in.set4_20mA(); + MachineControl_AnalogIn.begin(MCAI_SENSOR_4_20MA); } void loop() { - float raw_voltage_ch0 = analog_in.read(0); + float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535; float current_ch0 = (voltage_ch0 / SENSE_RES) * 1000; Serial.print("Measured Current CH0: "); Serial.print(current_ch0); Serial.println("mA"); - float raw_voltage_ch1 = analog_in.read(1); + float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535; float current_ch1 = (voltage_ch1 / SENSE_RES) * 1000; Serial.print("Measured Current CH1: "); Serial.print(current_ch1); Serial.println("mA"); - float raw_voltage_ch2 = analog_in.read(2); + float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535; float current_ch2 = (voltage_ch2 / SENSE_RES) * 1000; Serial.print("Measured Current CH2: "); diff --git a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino index d15149c..8508edb 100644 --- a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino +++ b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino @@ -22,22 +22,18 @@ */ #include -using namespace machinecontrol; - #define REFERENCE_RES 100000 float reference = 3.3; float lowest_voltage = 2.7; void setup() { - analogReadResolution(16); - Serial.begin(9600); - analog_in.setNTC(); + MachineControl_AnalogIn.begin(MCAI_SENSOR_NTC); } void loop() { - float raw_voltage_ch0 = analog_in.read(0); + float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535; float resistance_ch0; Serial.print("Resistance CH0: "); @@ -50,7 +46,7 @@ void loop() { Serial.println("NaN"); } - float raw_voltage_ch1 = analog_in.read(1); + float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535; float resistance_ch1; Serial.print("Resistance CH1: "); @@ -63,7 +59,7 @@ void loop() { Serial.println("NaN"); } - float raw_voltage_ch2 = analog_in.read(2); + float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535; float resistance_ch2; Serial.print("Resistance CH2: "); diff --git a/src/AnalogInClass.cpp b/src/AnalogInClass.cpp new file mode 100644 index 0000000..c43518a --- /dev/null +++ b/src/AnalogInClass.cpp @@ -0,0 +1,144 @@ +/** + * @file AnalogInClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Analog IN connector of the Portenta Machine Control library. + */ + +/* Includes -----------------------------------------------------------------*/ +#include "AnalogInClass.h" + +/* Private defines -----------------------------------------------------------*/ +#define CH0_IN1 PD_4 +#define CH0_IN2 PD_5 +#define CH0_IN3 PE_3 +#define CH0_IN4 PG_3 + +#define CH1_IN1 PD_7 +#define CH1_IN2 PH_6 +#define CH1_IN3 PJ_7 +#define CH1_IN4 PH_15 + +#define CH2_IN1 PH_10 +#define CH2_IN2 PA_4 +#define CH2_IN3 PA_8 +#define CH2_IN4 PC_6 + +/* Functions -----------------------------------------------------------------*/ +AnalogInClass::AnalogInClass(PinName ai0_pin, PinName ai1_pin, PinName ai2_pin) + : _ai0{ai0_pin}, _ai1{ai1_pin}, _ai2{ai2_pin} +{ + // Pin configuration for CH0 + pinMode(CH0_IN1, OUTPUT); + pinMode(CH0_IN2, OUTPUT); + pinMode(CH0_IN3, OUTPUT); + pinMode(CH0_IN4, OUTPUT); + + // Pin configuration for CH1 + pinMode(CH1_IN1, OUTPUT); + pinMode(CH1_IN2, OUTPUT); + pinMode(CH1_IN3, OUTPUT); + pinMode(CH1_IN4, OUTPUT); + + // Pin configuration for CH2 + pinMode(CH2_IN1, OUTPUT); + pinMode(CH2_IN2, OUTPUT); + pinMode(CH2_IN3, OUTPUT); + pinMode(CH2_IN4, OUTPUT); +} + +AnalogInClass::~AnalogInClass() +{ } + +bool AnalogInClass::begin(int sensor_type, int res_bits) { + bool ret = true; + + /* Set bit resolution of ADC */ + analogReadResolution(res_bits); + + switch (sensor_type) { + case MCAI_SENSOR_NTC: + /* Enable a 100K resistor in series with the reference voltage. + * The voltage sampled is the voltage division between the 100k resistor and the input resistor (NTC/PTC) */ + digitalWrite(CH0_IN1, LOW); + digitalWrite(CH0_IN2, LOW); + digitalWrite(CH0_IN3, HIGH); + digitalWrite(CH0_IN4, HIGH); + + digitalWrite(CH1_IN1, LOW); + digitalWrite(CH1_IN2, LOW); + digitalWrite(CH1_IN3, HIGH); + digitalWrite(CH1_IN4, HIGH); + + digitalWrite(CH2_IN1, LOW); + digitalWrite(CH2_IN2, LOW); + digitalWrite(CH2_IN3, HIGH); + digitalWrite(CH2_IN4, HIGH); + break; + case MCAI_SENSOR_0_10V: + /* Configure the input resistor dividers to have a ratio of 0.28 + * (Maximum input voltage is 10V). */ + digitalWrite(CH0_IN1, HIGH); + digitalWrite(CH0_IN2, HIGH); + digitalWrite(CH0_IN3, LOW); + digitalWrite(CH0_IN4, HIGH); + + digitalWrite(CH1_IN1, HIGH); + digitalWrite(CH1_IN2, HIGH); + digitalWrite(CH1_IN3, LOW); + digitalWrite(CH1_IN4, HIGH); + + digitalWrite(CH2_IN1, HIGH); + digitalWrite(CH2_IN2, HIGH); + digitalWrite(CH2_IN3, LOW); + digitalWrite(CH2_IN4, HIGH); + break; + case MCAI_SENSOR_4_20MA: + /* Enable a 120 ohm resistor to GND to convert the 4-20mA sensor currents to voltage. + * Note: 24V are available from the carrier to power the 4-20mA sensors. */ + digitalWrite(CH0_IN1, HIGH); + digitalWrite(CH0_IN2, LOW); + digitalWrite(CH0_IN3, HIGH); + digitalWrite(CH0_IN4, LOW); + + digitalWrite(CH1_IN1, HIGH); + digitalWrite(CH1_IN2, LOW); + digitalWrite(CH1_IN3, HIGH); + digitalWrite(CH1_IN4, LOW); + + digitalWrite(CH2_IN1, HIGH); + digitalWrite(CH2_IN2, LOW); + digitalWrite(CH2_IN3, HIGH); + digitalWrite(CH2_IN4, LOW); + break; + default: + /* Unknown sensor type */ + ret = false; + break; + } + + return ret; +} + +uint16_t AnalogInClass::read(int channel) { + uint16_t value = 0; + + switch (channel) { + case 0: + value = analogRead(_ai0); + break; + case 1: + value = analogRead(_ai1); + break; + case 2: + value = analogRead(_ai2); + break; + default: + break; + } + + return value; +} + +AnalogInClass MachineControl_AnalogIn; + +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/AnalogInClass.h b/src/AnalogInClass.h new file mode 100644 index 0000000..54e2795 --- /dev/null +++ b/src/AnalogInClass.h @@ -0,0 +1,66 @@ +/** + * @file AnalogInClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Analog IN connector of the Portenta Machine Control library. + * + * This library allows to set the resistor configuration for the type of connected analog sensor (0-10V, 4-20mA or NTC) + * and to capture the analog values acquired by the ANALOG IN channels. + */ +#ifndef __ANALOGIN_CLASS_H +#define __ANALOGIN_CLASS_H + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +/* Exported defines ----------------------------------------------------------*/ + +/** Analog Sensor type **/ +#define MCAI_SENSOR_NTC 1 +#define MCAI_SENSOR_0_10V 2 +#define MCAI_SENSOR_4_20MA 3 + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class AnalogInClass + * @brief Class for the Analog IN connector of the Portenta Machine Control. + */ +class AnalogInClass { + public: + /** + * @brief Construct an Analog Input reader for the Portenta Machine Control. + * + * @param ai0_pin The analog pin number of the channel 0 + * @param ai1_pin The analog pin number of the channel 1 + * @param ai2_pin The analog pin number of the channel 2 + */ + AnalogInClass(PinName ai0_pin = PC_3C, PinName ai1_pin = PC_2C, PinName ai2_pin = PA_1C); + ~AnalogInClass(); + + /** + * @brief Initialize the analog reader, configure the sensor type and read resolution. + * + * @param sensor_type The sensor type (0-10V, 4-20mA or NTC) + * @param res_bits Resolution in bits of the read analog value + * @return true If the analog reader is successfully initialized, false Otherwise + */ + bool begin(int sensor_type, int res_bits = 16); + + /** + * @brief Read the sampled voltage from the selected channel. + * + * @param channel The analog input channel number + * @return uint16_t The analog value between 0.0 and 1.0 normalized to a 16-bit value + */ + uint16_t read(int channel); + + private: + PinName _ai0; + PinName _ai1; + PinName _ai2; +}; + +extern AnalogInClass MachineControl_AnalogIn; + +#endif /* __ANALOGIN_CLASS_H */ \ No newline at end of file diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index d7088c2..f80cc69 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -13,6 +13,8 @@ #include #include +#include "AnalogInClass.h" + #if __has_include("portenta_info.h") #include "portenta_info.h" #define TRY_REV2_RECOGNITION @@ -173,137 +175,6 @@ class COMMClass { extern COMMClass comm_protocols; -#define ch0_in1 ch_in[0] -#define ch0_in2 ch_in[1] -#define ch0_in3 ch_in[2] -#define ch0_in4 ch_in[3] -#define ch1_in1 ch_in[4] -#define ch1_in2 ch_in[5] -#define ch1_in3 ch_in[6] -#define ch1_in4 ch_in[7] -#define ch2_in1 ch_in[8] -#define ch2_in2 ch_in[9] -#define ch2_in3 ch_in[10] -#define ch2_in4 ch_in[11] - -/** - * The AnalogInClass is used to set the resistor configuration for the right type of analog sensor - * i.e. NTC sensors, 4-10mA or 0-10V. - */ -class AnalogInClass { -public: - - /** - * read the sampled voltage from the selected channel - * @param channel integer for selecting the analog input (0, 1 or 2) - * @return the analog value between 0.0 and 1.0 normalized to a 16-bit value (uint16_t) - */ - uint16_t read(int channel) { - uint16_t value = 0; - switch (channel) { - case 0: - value = in_0.read_u16(); - break; - case 1: - value = in_1.read_u16(); - break; - case 2: - value = in_2.read_u16(); - break; - default: - break; - } - return value; - } - - /** - * Configure the input resistor dividers to have a ratio of 0.28. - * Maximum input voltage is 10V. - */ - void set0_10V() { - ch0_in1 = 1; - ch0_in2 = 1; - ch0_in3 = 0; - ch0_in4 = 1; - - ch1_in1 = 1; - ch1_in2 = 1; - ch1_in3 = 0; - ch1_in4 = 1; - - ch2_in1 = 1; - ch2_in2 = 1; - ch2_in3 = 0; - ch2_in4 = 1; - } - - /** - * Enable a 120 ohm resistor to GND to convert the 4-20mA sensor currents to voltage. - * Note: 24V are available from the carrier to power the 4-20mA sensors. - */ - void set4_20mA() { - ch0_in1 = 1; - ch0_in2 = 0; - ch0_in3 = 1; - ch0_in4 = 0; - - ch1_in1 = 1; - ch1_in2 = 0; - ch1_in3 = 1; - ch1_in4 = 0; - - ch2_in1 = 1; - ch2_in2 = 0; - ch2_in3 = 1; - ch2_in4 = 0; - } - - /** - * Enable a 100K resistor in series with the reference voltage. - * The voltage sampled is the voltage division between the 100k resistor and the input resistor (NTC/PTC) - */ - void setNTC() { - ch0_in1 = 0; - ch0_in2 = 0; - ch0_in3 = 1; - ch0_in4 = 1; - - ch1_in1 = 0; - ch1_in2 = 0; - ch1_in3 = 1; - ch1_in4 = 1; - - ch2_in1 = 0; - ch2_in2 = 0; - ch2_in3 = 1; - ch2_in4 = 1; - } - - mbed::AnalogIn& operator[](int index) { - switch (index) { - case 0: - return in_0; - case 1: - return in_1; - case 2: - return in_2; - } - } - - mbed::DigitalOut ch_in[12] = { - mbed::DigitalOut(PD_4), mbed::DigitalOut(PD_5), mbed::DigitalOut(PE_3), mbed::DigitalOut(PG_3), - mbed::DigitalOut(PD_7), mbed::DigitalOut(PH_6), mbed::DigitalOut(PJ_7), mbed::DigitalOut(PH_15), - mbed::DigitalOut(PH_10), mbed::DigitalOut(PA_4), mbed::DigitalOut(PA_8), mbed::DigitalOut(PC_6) - }; - -private: - mbed::AnalogIn in_0 = mbed::AnalogIn(PC_3C); - mbed::AnalogIn in_1 = mbed::AnalogIn(PC_2C); - mbed::AnalogIn in_2 = mbed::AnalogIn(PA_1C); -}; - -extern AnalogInClass analog_in; - class AnalogOutClass { public: diff --git a/src/Objects.cpp b/src/Objects.cpp index a8880fc..dc651f9 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -4,7 +4,6 @@ namespace machinecontrol { RTDClass temp_probes; COMMClass comm_protocols; -AnalogInClass analog_in; AnalogOutClass analog_out; EncoderClass encoders; DigitalOutputsClass digital_outputs; From 0b73e348a43a307a7e030c8dea497f0fc05d2662 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 12 Jul 2023 12:40:14 +0200 Subject: [PATCH 02/47] create AnalogOutClass as separate module --- src/AnalogOutClass.cpp | 64 +++++++++++++++++++++++++++++++ src/AnalogOutClass.h | 48 ++++++++++++++++++++++++ src/Arduino_MachineControl.h | 73 +----------------------------------- src/Objects.cpp | 2 - 4 files changed, 113 insertions(+), 74 deletions(-) create mode 100644 src/AnalogOutClass.cpp create mode 100644 src/AnalogOutClass.h diff --git a/src/AnalogOutClass.cpp b/src/AnalogOutClass.cpp new file mode 100644 index 0000000..543e250 --- /dev/null +++ b/src/AnalogOutClass.cpp @@ -0,0 +1,64 @@ +/** + * @file AnalogOutClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the + */ + +/* Includes -----------------------------------------------------------------*/ +#include "AnalogOutClass.h" + +/* Functions -----------------------------------------------------------------*/ +void AnalogOutClass::write(int index, float voltage) { + if (voltage < 0) { + voltage = 0; + } + + switch (index) { + case 0: + out_0.write(voltage / 10.5); + break; + case 1: + out_1.write(voltage / 10.5); + break; + case 2: + out_2.write(voltage / 10.5); + break; + case 3: + out_3.write(voltage / 10.5); + break; + } +} + +void AnalogOutClass::period_ms(int index, uint8_t period) { + switch (index) { + case 0: + out_0.period_ms(period); + break; + case 1: + out_1.period_ms(period); + break; + case 2: + out_2.period_ms(period); + break; + case 3: + out_3.period_ms(period); + break; + } +} + +mbed::PwmOut& AnalogOutClass::operator[](int index) { + switch (index) { + case 0: + return out_0; + case 1: + return out_1; + case 2: + return out_2; + case 3: + return out_3; + } +} + +AnalogOutClass analog_out; + +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/AnalogOutClass.h b/src/AnalogOutClass.h new file mode 100644 index 0000000..941331a --- /dev/null +++ b/src/AnalogOutClass.h @@ -0,0 +1,48 @@ +/** + * @file AnalogInClass.h + * @author Leonardo Cavagnis + * @brief Header file for the + * + * This library allows to + */ +#ifndef __ANALOGOUT_CLASS_H +#define __ANALOGOUT_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class AnalogOutClass + * @brief Class for the + */ +class AnalogOutClass { + public: + /** + * Set output voltage value (PWM) + * @param index select channel + * @param voltage desired output voltage (max 10.5V) + */ + void write(int index, float voltage); + + /** + * Set the PWM period (frequency) + * @param index select channel + * @param period integer for selecting the period in ms + */ + void period_ms(int index, uint8_t period); + + mbed::PwmOut& operator[](int index); + + private: + mbed::PwmOut out_0 = mbed::PwmOut(PJ_11); + mbed::PwmOut out_1 = mbed::PwmOut(PK_1); + mbed::PwmOut out_2 = mbed::PwmOut(PG_7); + mbed::PwmOut out_3 = mbed::PwmOut(PC_7); +}; + +extern AnalogOutClass analog_out; + +#endif /* __ANALOGOUT_CLASS_H */ \ No newline at end of file diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index f80cc69..b61c7e2 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -14,6 +14,7 @@ #include #include "AnalogInClass.h" +#include "AnalogOutClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -175,78 +176,6 @@ class COMMClass { extern COMMClass comm_protocols; -class AnalogOutClass { -public: - - /** - * Set output voltage value (PWM) - * @param index select channel - * @param voltage desired output voltage (max 10.5V) - */ - void write(int index, float voltage) { - if (voltage < 0) { - voltage = 0; - } - - switch (index) { - case 0: - out_0.write(voltage / 10.5); - break; - case 1: - out_1.write(voltage / 10.5); - break; - case 2: - out_2.write(voltage / 10.5); - break; - case 3: - out_3.write(voltage / 10.5); - break; - } - } - - /** - * Set the PWM period (frequency) - * @param index select channel - * @param period integer for selecting the period in ms - */ - void period_ms(int index, uint8_t period) { - switch (index) { - case 0: - out_0.period_ms(period); - break; - case 1: - out_1.period_ms(period); - break; - case 2: - out_2.period_ms(period); - break; - case 3: - out_3.period_ms(period); - break; - } - } - mbed::PwmOut& operator[](int index) { - switch (index) { - case 0: - return out_0; - case 1: - return out_1; - case 2: - return out_2; - case 3: - return out_3; - } - } -private: - mbed::PwmOut out_0 = mbed::PwmOut(PJ_11); - mbed::PwmOut out_1 = mbed::PwmOut(PK_1); - mbed::PwmOut out_2 = mbed::PwmOut(PG_7); - mbed::PwmOut out_3 = mbed::PwmOut(PC_7); -}; - -extern AnalogOutClass analog_out; - - /* TODO: writeme Use QEI library for mbed since it implements index pin diff --git a/src/Objects.cpp b/src/Objects.cpp index dc651f9..4d5d56f 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -1,10 +1,8 @@ #include "Arduino_MachineControl.h" namespace machinecontrol { - RTDClass temp_probes; COMMClass comm_protocols; -AnalogOutClass analog_out; EncoderClass encoders; DigitalOutputsClass digital_outputs; ProgrammableDINClass digital_inputs; From 86db1ccfe2afd38c5ab696432195348fd1314f19 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 12 Jul 2023 15:19:01 +0200 Subject: [PATCH 03/47] AnalogOut class refactoring --- examples/Analog_Out/Analog_Out.ino | 41 ++++++++--------- src/AnalogOutClass.cpp | 70 +++++++++++++++++------------- src/AnalogOutClass.h | 52 ++++++++++++++-------- 3 files changed, 92 insertions(+), 71 deletions(-) diff --git a/examples/Analog_Out/Analog_Out.ino b/examples/Analog_Out/Analog_Out.ino index 89110e7..7c4a9c5 100644 --- a/examples/Analog_Out/Analog_Out.ino +++ b/examples/Analog_Out/Analog_Out.ino @@ -15,38 +15,33 @@ #include -using namespace machinecontrol; +float voltage = 0; void setup() { - //analog_out.period_ms(CHANNEL, PERIOD_MILLISECONDS); - analog_out.period_ms(0, 4); - analog_out.period_ms(1, 4); - analog_out.period_ms(2, 4); - analog_out.period_ms(3, 4); + MachineControl_AnalogOut.begin(); + + MachineControl_AnalogOut.setPeriod(0, 4); //4ms - 250Hz + MachineControl_AnalogOut.setPeriod(1, 4); + MachineControl_AnalogOut.setPeriod(2, 4); + MachineControl_AnalogOut.setPeriod(3, 4); Serial.begin(9600); Serial.println("Analog out test"); - } -//Output values which will be changed with this variable -float counter = 1; - void loop() { - //analog_out.write(CHANNEL, OUTPUT_VOLTAGE_VALUE); - analog_out.write(0, counter); - analog_out.write(1, counter); - analog_out.write(2, counter); - analog_out.write(3, counter); - Serial.println("All channels set at "+String(counter)+"V"); + MachineControl_AnalogOut.write(0, voltage); + MachineControl_AnalogOut.write(1, voltage); + MachineControl_AnalogOut.write(2, voltage); + MachineControl_AnalogOut.write(3, voltage); + + Serial.println("All channels set at " + String(voltage) + "V"); - counter = counter + 0.1; - //Maximum output value is 10.4V - if (counter >= 10.5) - { - counter = 0; - //Additional 100 ms delay introduced to manage 10.5V -> 0V fall time of 150 ms - delay(100); + voltage = voltage + 0.1; + //Maximum output value is 10.5V + if (voltage >= 10.5) { + voltage = 0; + delay(100); //Additional 100 ms delay introduced to manage 10.5V -> 0V fall time of 150 ms } delay(100); } diff --git a/src/AnalogOutClass.cpp b/src/AnalogOutClass.cpp index 543e250..e6674c0 100644 --- a/src/AnalogOutClass.cpp +++ b/src/AnalogOutClass.cpp @@ -1,64 +1,74 @@ /** * @file AnalogOutClass.cpp * @author Leonardo Cavagnis - * @brief Source file for the + * @brief Source file for the Analog OUT connector of the Portenta Machine Control library. */ /* Includes -----------------------------------------------------------------*/ #include "AnalogOutClass.h" +/* Private defines -----------------------------------------------------------*/ +#define MCAO_MAX_VOLTAGE 10.5 + /* Functions -----------------------------------------------------------------*/ -void AnalogOutClass::write(int index, float voltage) { - if (voltage < 0) { - voltage = 0; - } +AnalogOutClass::AnalogOutClass(PinName ao0_pin, PinName ao1_pin, PinName ao2_pin, PinName ao3_pin) + : _ao0{mbed::PwmOut(ao0_pin)}, _ao1{mbed::PwmOut(ao1_pin)}, _ao2{mbed::PwmOut(ao2_pin)}, _ao3{mbed::PwmOut(ao3_pin)} +{ } + +AnalogOutClass::~AnalogOutClass() +{ } + +bool AnalogOutClass::begin() { + setPeriod(0, 2); //2ms - 500Hz + setPeriod(1, 2); + setPeriod(2, 2); + setPeriod(3, 2); - switch (index) { + return true; +} + +void AnalogOutClass::setPeriod(int channel, uint8_t period_ms) { + switch (channel) { case 0: - out_0.write(voltage / 10.5); + _ao0.period_ms(period_ms); break; case 1: - out_1.write(voltage / 10.5); + _ao1.period_ms(period_ms); break; case 2: - out_2.write(voltage / 10.5); + _ao2.period_ms(period_ms); break; case 3: - out_3.write(voltage / 10.5); + _ao3.period_ms(period_ms); break; } } -void AnalogOutClass::period_ms(int index, uint8_t period) { - switch (index) { +void AnalogOutClass::write(int channel, float voltage) { + if (voltage < 0) { + voltage = 0; + } + + if (voltage > MCAO_MAX_VOLTAGE) { + voltage = MCAO_MAX_VOLTAGE; + } + + switch (channel) { case 0: - out_0.period_ms(period); + _ao0.write(voltage / MCAO_MAX_VOLTAGE); break; case 1: - out_1.period_ms(period); + _ao1.write(voltage / MCAO_MAX_VOLTAGE); break; case 2: - out_2.period_ms(period); + _ao2.write(voltage / MCAO_MAX_VOLTAGE); break; case 3: - out_3.period_ms(period); + _ao3.write(voltage / MCAO_MAX_VOLTAGE); break; } } -mbed::PwmOut& AnalogOutClass::operator[](int index) { - switch (index) { - case 0: - return out_0; - case 1: - return out_1; - case 2: - return out_2; - case 3: - return out_3; - } -} - -AnalogOutClass analog_out; +AnalogOutClass MachineControl_AnalogOut; /**** END OF FILE ****/ \ No newline at end of file diff --git a/src/AnalogOutClass.h b/src/AnalogOutClass.h index 941331a..bfc0228 100644 --- a/src/AnalogOutClass.h +++ b/src/AnalogOutClass.h @@ -1,9 +1,9 @@ /** - * @file AnalogInClass.h + * @file AnalogOutClass.h * @author Leonardo Cavagnis - * @brief Header file for the + * @brief Header file for the Analog OUT connector of the Portenta Machine Control library. * - * This library allows to + * This library allows to configure the analog channels as PWM, to set frequency and value. */ #ifndef __ANALOGOUT_CLASS_H #define __ANALOGOUT_CLASS_H @@ -16,33 +16,49 @@ /** * @class AnalogOutClass - * @brief Class for the + * @brief Class for the Analog OUT connector of the Portenta Machine Control. */ class AnalogOutClass { public: /** - * Set output voltage value (PWM) - * @param index select channel - * @param voltage desired output voltage (max 10.5V) + * @brief Construct an Analog Output writer for the Portenta Machine Control. + * + * @param ao0_pin The analog pin number of the channel 0 + * @param ao1_pin The analog pin number of the channel 1 + * @param ao2_pin The analog pin number of the channel 2 + * @param ao3_pin The analog pin number of the channel 2 */ - void write(int index, float voltage); + AnalogOutClass(PinName ao0_pin = PJ_11, PinName ao1_pin = PK_1, PinName ao2_pin = PG_7, PinName ao3_pin = PC_7); + ~AnalogOutClass(); /** - * Set the PWM period (frequency) - * @param index select channel - * @param period integer for selecting the period in ms + * @brief Initialize the PWM, configure the default frequency for all channels (500Hz) + * + * @return true If the PWM is successfully initialized, false Otherwise */ - void period_ms(int index, uint8_t period); + bool begin(); - mbed::PwmOut& operator[](int index); + /** + * Set the PWM period (frequency) on the selected channel + * @param channel selected channel + * @param period_ms PWM period in ms + */ + void setPeriod(int channel, uint8_t period_ms); + + /** + * Set output voltage value on the selected channel + * @param channel selected channel + * @param voltage desired output voltage (max 10.5V) + */ + void write(int channel, float voltage); private: - mbed::PwmOut out_0 = mbed::PwmOut(PJ_11); - mbed::PwmOut out_1 = mbed::PwmOut(PK_1); - mbed::PwmOut out_2 = mbed::PwmOut(PG_7); - mbed::PwmOut out_3 = mbed::PwmOut(PC_7); + mbed::PwmOut _ao0; + mbed::PwmOut _ao1; + mbed::PwmOut _ao2; + mbed::PwmOut _ao3; }; -extern AnalogOutClass analog_out; +extern AnalogOutClass MachineControl_AnalogOut; #endif /* __ANALOGOUT_CLASS_H */ \ No newline at end of file From fdc1c44efca9d97e51774ba2f5d6a47cc79b3587 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 12 Jul 2023 15:20:17 +0200 Subject: [PATCH 04/47] docs: cosmetics --- src/AnalogOutClass.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/AnalogOutClass.h b/src/AnalogOutClass.h index bfc0228..a22956d 100644 --- a/src/AnalogOutClass.h +++ b/src/AnalogOutClass.h @@ -39,14 +39,16 @@ class AnalogOutClass { bool begin(); /** - * Set the PWM period (frequency) on the selected channel + * @brief Set the PWM period (frequency) on the selected channel + * * @param channel selected channel * @param period_ms PWM period in ms */ void setPeriod(int channel, uint8_t period_ms); /** - * Set output voltage value on the selected channel + * @brief Set output voltage value on the selected channel + * * @param channel selected channel * @param voltage desired output voltage (max 10.5V) */ From e1d11c1e99df4ea5503125cf150ee001f5ac300f Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 12 Jul 2023 15:48:18 +0200 Subject: [PATCH 05/47] create DigitalOutputsClass as separate module --- src/Arduino_MachineControl.h | 60 +----------------------------------- src/DigitalOutputsClass.cpp | 26 ++++++++++++++++ src/DigitalOutputsClass.h | 49 +++++++++++++++++++++++++++++ 3 files changed, 76 insertions(+), 59 deletions(-) create mode 100644 src/DigitalOutputsClass.cpp create mode 100644 src/DigitalOutputsClass.h diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index b61c7e2..1ea97c0 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -15,6 +15,7 @@ #include "AnalogInClass.h" #include "AnalogOutClass.h" +#include "DigitalOutputsClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -257,65 +258,6 @@ class ProgrammableDIOClass : public ArduinoIOExpanderClass { extern ProgrammableDIOClass digital_programmables; - -/** - * The DigitalOutputClass is used to interface with the IO Expander and - * set the digital outputs. - */ -class DigitalOutputsClass { -public: - - /** - * Set all digital outputs at the same time. - * @param val 8 bit integer to set all 8 channels. e.g: - * Set all to HIGH -> val = 255 (0b11111111) - * Set all to LOW -> val = 0 (0b00000000) - */ - void setAll(uint8_t val) { - for (int i = 0; i < 8; i++) { - out[i] = val & 0x1; - val = val >> 1; - } - } - - /** - * Set a particular digital output - * @param index digital output to be set - * @param val set value (HIGH/LOW) - */ - void set(int index, bool val) { - out[index] = val; - } - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. - * The output latches off when thermal shutdown occurs. - */ - void setLatch() { - dig_out_latch_retry = 0; - } - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. - * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) - * to avoid repetitive thermal shutdown. - */ - void setRetry() { - dig_out_latch_retry = 1; - } - mbed::DigitalOut& operator[](int index) { - return out[index]; - } -private: - mbed::DigitalOut dig_out_latch_retry = mbed::DigitalOut(PB_2); - mbed::DigitalOut out[8] = { - mbed::DigitalOut(PI_6), mbed::DigitalOut(PH_9), mbed::DigitalOut(PJ_9), mbed::DigitalOut(PE_2), - mbed::DigitalOut(PI_3), mbed::DigitalOut(PI_2), mbed::DigitalOut(PD_3), mbed::DigitalOut(PA_14) - }; -}; - -extern DigitalOutputsClass digital_outputs; - class ProgrammableDINClass : public ArduinoIOExpanderClass { public: /** diff --git a/src/DigitalOutputsClass.cpp b/src/DigitalOutputsClass.cpp new file mode 100644 index 0000000..f0a6276 --- /dev/null +++ b/src/DigitalOutputsClass.cpp @@ -0,0 +1,26 @@ +#include "DigitalOutputsClass.h" + +void DigitalOutputsClass::setAll(uint8_t val) { + for (int i = 0; i < 8; i++) { + out[i] = val & 0x1; + val = val >> 1; + } +} + +void DigitalOutputsClass::set(int index, bool val) { + out[index] = val; +} + +void DigitalOutputsClass::setLatch() { + dig_out_latch_retry = 0; +} + +void DigitalOutputsClass::setRetry() { + dig_out_latch_retry = 1; +} + +mbed::DigitalOut& DigitalOutputsClass::operator[](int index) { + return out[index]; +} + +DigitalOutputsClass digital_outputs; \ No newline at end of file diff --git a/src/DigitalOutputsClass.h b/src/DigitalOutputsClass.h new file mode 100644 index 0000000..5fa5f92 --- /dev/null +++ b/src/DigitalOutputsClass.h @@ -0,0 +1,49 @@ +#include +#include + +/** + * The DigitalOutputClass is used to interface with the IO Expander and + * set the digital outputs. + */ +class DigitalOutputsClass { +public: + + /** + * Set all digital outputs at the same time. + * @param val 8 bit integer to set all 8 channels. e.g: + * Set all to HIGH -> val = 255 (0b11111111) + * Set all to LOW -> val = 0 (0b00000000) + */ + void setAll(uint8_t val); + + /** + * Set a particular digital output + * @param index digital output to be set + * @param val set value (HIGH/LOW) + */ + void set(int index, bool val); + + /** + * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. + * The output latches off when thermal shutdown occurs. + */ + void setLatch(); + + /** + * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. + * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) + * to avoid repetitive thermal shutdown. + */ + void setRetry(); + + mbed::DigitalOut& operator[](int index); + +private: + mbed::DigitalOut dig_out_latch_retry = mbed::DigitalOut(PB_2); + mbed::DigitalOut out[8] = { + mbed::DigitalOut(PI_6), mbed::DigitalOut(PH_9), mbed::DigitalOut(PJ_9), mbed::DigitalOut(PE_2), + mbed::DigitalOut(PI_3), mbed::DigitalOut(PI_2), mbed::DigitalOut(PD_3), mbed::DigitalOut(PA_14) + }; +}; + +extern DigitalOutputsClass digital_outputs; \ No newline at end of file From b01735b6b29d25899fb51bfeb6fcec2a92b39854 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 12 Jul 2023 17:12:41 +0200 Subject: [PATCH 06/47] DigitalOutputs class refactoring --- examples/Digital_output/Digital_output.ino | 46 ++++---- src/DigitalOutputsClass.cpp | 91 +++++++++++++--- src/DigitalOutputsClass.h | 118 ++++++++++++++------- src/Objects.cpp | 1 - 4 files changed, 180 insertions(+), 76 deletions(-) diff --git a/examples/Digital_output/Digital_output.ino b/examples/Digital_output/Digital_output.ino index 5bf6b51..5f7aab3 100644 --- a/examples/Digital_output/Digital_output.ino +++ b/examples/Digital_output/Digital_output.ino @@ -29,22 +29,22 @@ #include -using namespace machinecontrol; - void setup() { Serial.begin(9600); // The loop starts only when the Serial Monitor is opened. while (!Serial); + MachineControl_DigitalOutputs.begin(); + //Set over current behavior of all channels to latch mode: - digital_outputs.setLatch(); + MachineControl_DigitalOutputs.setLatch(); // Uncomment this line to set over current behavior of all // channels to auto retry mode instead of latch mode: - //digital_outputs.setRetry(); + //MachineControl_DigitalOutputs.setRetry(); //At startup set all channels to OPEN - digital_outputs.setAll(0); + MachineControl_DigitalOutputs.writeAll(0); } @@ -52,63 +52,63 @@ void loop() { Serial.println("DIGITAL OUT:"); // Set all channels to CLOSED - digital_outputs.setAll(255); + MachineControl_DigitalOutputs.writeAll(255); Serial.print("All channels are CLOSED for 1 s..."); delay(1000); // Set all channels to OPEN - digital_outputs.setAll(0); + MachineControl_DigitalOutputs.writeAll(0); Serial.println("now they are OPEN."); delay(1000); // Toggle each channel for 1 s, one by one - digital_outputs.set(0, HIGH); + MachineControl_DigitalOutputs.write(0, HIGH); Serial.print("CH0 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(0, LOW); + MachineControl_DigitalOutputs.write(0, LOW); Serial.println("now is OPEN."); - digital_outputs.set(1, HIGH); + MachineControl_DigitalOutputs.write(1, HIGH); Serial.print("CH1 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(1, LOW); + MachineControl_DigitalOutputs.write(1, LOW); Serial.println("now is OPEN."); - digital_outputs.set(2, HIGH); + MachineControl_DigitalOutputs.write(2, HIGH); Serial.print("CH2 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(2, LOW); + MachineControl_DigitalOutputs.write(2, LOW); Serial.println("now is OPEN."); - digital_outputs.set(3, HIGH); + MachineControl_DigitalOutputs.write(3, HIGH); Serial.print("CH3 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(3, LOW); + MachineControl_DigitalOutputs.write(3, LOW); Serial.println("now is OPEN."); - digital_outputs.set(4, HIGH); + MachineControl_DigitalOutputs.write(4, HIGH); Serial.print("CH4 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(4, LOW); + MachineControl_DigitalOutputs.write(4, LOW); Serial.println("now is OPEN."); - digital_outputs.set(5, HIGH); + MachineControl_DigitalOutputs.write(5, HIGH); Serial.print("CH5 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(5, LOW); + MachineControl_DigitalOutputs.write(5, LOW); Serial.println("now is OPEN."); - digital_outputs.set(6, HIGH); + MachineControl_DigitalOutputs.write(6, HIGH); Serial.print("CH6 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(6, LOW); + MachineControl_DigitalOutputs.write(6, LOW); Serial.println("now is OPEN."); - digital_outputs.set(7, HIGH); + MachineControl_DigitalOutputs.write(7, HIGH); Serial.print("CH7 is CLOSED for 1 s..."); delay(1000); - digital_outputs.set(7, LOW); + MachineControl_DigitalOutputs.write(7, LOW); Serial.println("now is OPEN."); Serial.println(); diff --git a/src/DigitalOutputsClass.cpp b/src/DigitalOutputsClass.cpp index f0a6276..d0db57b 100644 --- a/src/DigitalOutputsClass.cpp +++ b/src/DigitalOutputsClass.cpp @@ -1,26 +1,91 @@ +/** + * @file DigitalOutputsClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Digital Output connector connector of the Portenta Machine Control library. + */ + +/* Includes -----------------------------------------------------------------*/ #include "DigitalOutputsClass.h" -void DigitalOutputsClass::setAll(uint8_t val) { - for (int i = 0; i < 8; i++) { - out[i] = val & 0x1; - val = val >> 1; +/* Functions -----------------------------------------------------------------*/ +DigitalOutputsClass::DigitalOutputsClass(PinName do0_pin, + PinName do1_pin, + PinName do2_pin, + PinName do3_pin, + PinName do4_pin, + PinName do5_pin, + PinName do6_pin, + PinName do7_pin, + PinName latch_pin) +: _do0{do0_pin}, _do1{do1_pin}, _do2{do2_pin}, _do3{do3_pin}, _do4{do4_pin}, _do5{do5_pin}, _do6{do6_pin}, _do7{do7_pin}, _latch{latch_pin} +{ } + +DigitalOutputsClass::~DigitalOutputsClass() +{ } + +bool DigitalOutputsClass::begin() { + pinMode(_do0, OUTPUT); + pinMode(_do1, OUTPUT); + pinMode(_do2, OUTPUT); + pinMode(_do3, OUTPUT); + pinMode(_do4, OUTPUT); + pinMode(_do5, OUTPUT); + pinMode(_do6, OUTPUT); + pinMode(_do7, OUTPUT); + + pinMode(_latch, OUTPUT); + + return true; +} + +void DigitalOutputsClass::write(uint8_t channel, PinStatus val) { + switch (channel) { + case 0: + digitalWrite(_do0, val); + break; + case 1: + digitalWrite(_do1, val); + break; + case 2: + digitalWrite(_do2, val); + break; + case 3: + digitalWrite(_do3, val); + break; + case 4: + digitalWrite(_do4, val); + break; + case 5: + digitalWrite(_do5, val); + break; + case 6: + digitalWrite(_do6, val); + break; + case 7: + digitalWrite(_do7, val); + break; + default: + break; } } -void DigitalOutputsClass::set(int index, bool val) { - out[index] = val; +void DigitalOutputsClass::writeAll(uint8_t val) { + for (uint8_t ch = 0; ch < 8; ch++) { + if (val && (1 << ch)) { + write(ch, HIGH); + } else { + write(ch, LOW); + } + } } void DigitalOutputsClass::setLatch() { - dig_out_latch_retry = 0; + digitalWrite(_latch, LOW); } void DigitalOutputsClass::setRetry() { - dig_out_latch_retry = 1; -} - -mbed::DigitalOut& DigitalOutputsClass::operator[](int index) { - return out[index]; + digitalWrite(_latch, HIGH); } -DigitalOutputsClass digital_outputs; \ No newline at end of file +DigitalOutputsClass MachineControl_DigitalOutputs; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/DigitalOutputsClass.h b/src/DigitalOutputsClass.h index 5fa5f92..e68d450 100644 --- a/src/DigitalOutputsClass.h +++ b/src/DigitalOutputsClass.h @@ -1,49 +1,89 @@ +/** + * @file DigitalOutputsClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Digital Output connector of the Portenta Machine Control library. + * + * This library allows to interface with the IO Expander and set the digital outputs. + */ +#ifndef __DIGITALOUTPUTS_CLASS_H +#define __DIGITALOUTPUTS_CLASS_H + +/* Includes -------------------------------------------------------------------*/ #include #include +/* Class ----------------------------------------------------------------------*/ + /** - * The DigitalOutputClass is used to interface with the IO Expander and - * set the digital outputs. + * @class DigitalOutputsClass + * @brief Class for the Digital Output connector of the Portenta Machine Control. */ class DigitalOutputsClass { -public: - - /** - * Set all digital outputs at the same time. - * @param val 8 bit integer to set all 8 channels. e.g: - * Set all to HIGH -> val = 255 (0b11111111) - * Set all to LOW -> val = 0 (0b00000000) - */ - void setAll(uint8_t val); - - /** - * Set a particular digital output - * @param index digital output to be set - * @param val set value (HIGH/LOW) - */ - void set(int index, bool val); - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. - * The output latches off when thermal shutdown occurs. - */ - void setLatch(); - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. - * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) - * to avoid repetitive thermal shutdown. - */ - void setRetry(); - - mbed::DigitalOut& operator[](int index); + public: + /** + * @brief Construct an + * + * @param + */ + DigitalOutputsClass(PinName do0_pin = PI_6, + PinName do1_pin = PH_9, + PinName do2_pin = PJ_9, + PinName do3_pin = PE_2, + PinName do4_pin = PI_3, + PinName do5_pin = PI_2, + PinName do6_pin = PD_3, + PinName do7_pin = PA_14, + PinName latch_pin = PB_2); + ~DigitalOutputsClass(); + /** + * @brief Initialize the + * + * @return true If the X is successfully initialized, false Otherwise + */ + bool begin(); + + /** + * @brief Set a particular digital output + * + * @param index digital output to be set + * @param val set value (HIGH/LOW) + */ + void write(uint8_t channel, PinStatus val); + + /** + * @brief Set all digital outputs at the same time. + * + * @param val 8 bit integer to set all 8 channels. e.g: + * Set all to HIGH -> val = 255 (0b11111111) + * Set all to LOW -> val = 0 (0b00000000) + */ + void writeAll(uint8_t val); + + /** + * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. + * The output latches off when thermal shutdown occurs. + */ + void setLatch(); + + /** + * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. + * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) + * to avoid repetitive thermal shutdown. + */ + void setRetry(); private: - mbed::DigitalOut dig_out_latch_retry = mbed::DigitalOut(PB_2); - mbed::DigitalOut out[8] = { - mbed::DigitalOut(PI_6), mbed::DigitalOut(PH_9), mbed::DigitalOut(PJ_9), mbed::DigitalOut(PE_2), - mbed::DigitalOut(PI_3), mbed::DigitalOut(PI_2), mbed::DigitalOut(PD_3), mbed::DigitalOut(PA_14) - }; + PinName _do0; + PinName _do1; + PinName _do2; + PinName _do3; + PinName _do4; + PinName _do5; + PinName _do6; + PinName _do7; + PinName _latch; }; -extern DigitalOutputsClass digital_outputs; \ No newline at end of file +extern DigitalOutputsClass MachineControl_DigitalOutputs; + +#endif /* __DIGITALOUTPUTS_CLASS_H */ \ No newline at end of file diff --git a/src/Objects.cpp b/src/Objects.cpp index 4d5d56f..cc7ff8a 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -4,7 +4,6 @@ namespace machinecontrol { RTDClass temp_probes; COMMClass comm_protocols; EncoderClass encoders; -DigitalOutputsClass digital_outputs; ProgrammableDINClass digital_inputs; ProgrammableDIOClass digital_programmables; RtcControllerClass rtc_controller; From 273f4fdb86ddaab710896c4a3f9a688537b3e2c0 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 13 Jul 2023 11:39:11 +0200 Subject: [PATCH 07/47] docs: DigitalOutputsClass --- examples/Digital_output/Digital_output.ino | 6 +- src/DigitalOutputsClass.cpp | 20 ++++--- src/DigitalOutputsClass.h | 68 +++++++++++++--------- 3 files changed, 55 insertions(+), 39 deletions(-) diff --git a/examples/Digital_output/Digital_output.ino b/examples/Digital_output/Digital_output.ino index 5f7aab3..7cf9080 100644 --- a/examples/Digital_output/Digital_output.ino +++ b/examples/Digital_output/Digital_output.ino @@ -34,14 +34,12 @@ void setup() { // The loop starts only when the Serial Monitor is opened. while (!Serial); - MachineControl_DigitalOutputs.begin(); - //Set over current behavior of all channels to latch mode: - MachineControl_DigitalOutputs.setLatch(); + MachineControl_DigitalOutputs.begin(true); // Uncomment this line to set over current behavior of all // channels to auto retry mode instead of latch mode: - //MachineControl_DigitalOutputs.setRetry(); + //MachineControl_DigitalOutputs.begin(false); //At startup set all channels to OPEN MachineControl_DigitalOutputs.writeAll(0); diff --git a/src/DigitalOutputsClass.cpp b/src/DigitalOutputsClass.cpp index d0db57b..97eb7a4 100644 --- a/src/DigitalOutputsClass.cpp +++ b/src/DigitalOutputsClass.cpp @@ -23,7 +23,7 @@ DigitalOutputsClass::DigitalOutputsClass(PinName do0_pin, DigitalOutputsClass::~DigitalOutputsClass() { } -bool DigitalOutputsClass::begin() { +bool DigitalOutputsClass::begin(bool latch_mode) { pinMode(_do0, OUTPUT); pinMode(_do1, OUTPUT); pinMode(_do2, OUTPUT); @@ -35,6 +35,12 @@ bool DigitalOutputsClass::begin() { pinMode(_latch, OUTPUT); + if(latch_mode) { + _setLatchMode(); + } else { + _setAutoRetryMode(); + } + return true; } @@ -69,9 +75,9 @@ void DigitalOutputsClass::write(uint8_t channel, PinStatus val) { } } -void DigitalOutputsClass::writeAll(uint8_t val) { +void DigitalOutputsClass::writeAll(uint8_t val_mask) { for (uint8_t ch = 0; ch < 8; ch++) { - if (val && (1 << ch)) { + if (val_mask && (1 << ch)) { write(ch, HIGH); } else { write(ch, LOW); @@ -79,12 +85,12 @@ void DigitalOutputsClass::writeAll(uint8_t val) { } } -void DigitalOutputsClass::setLatch() { - digitalWrite(_latch, LOW); +void DigitalOutputsClass::_setLatchMode() { + digitalWrite(_latch, HIGH); } -void DigitalOutputsClass::setRetry() { - digitalWrite(_latch, HIGH); +void DigitalOutputsClass::_setAutoRetryMode() { + digitalWrite(_latch, LOW); } DigitalOutputsClass MachineControl_DigitalOutputs; diff --git a/src/DigitalOutputsClass.h b/src/DigitalOutputsClass.h index e68d450..b08a0de 100644 --- a/src/DigitalOutputsClass.h +++ b/src/DigitalOutputsClass.h @@ -21,9 +21,19 @@ class DigitalOutputsClass { public: /** - * @brief Construct an + * @brief Construct a DigitalOutputsClass object. * - * @param + * This constructor initializes a DigitalOutputsClass object with the specified pin assignments for digital outputs. + * + * @param do0_pin The pin number for the digital output channel 0. + * @param do1_pin The pin number for the digital output channel 1. + * @param do2_pin The pin number for the digital output channel 2. + * @param do3_pin The pin number for the digital output channel 3. + * @param do4_pin The pin number for the digital output channel 4. + * @param do5_pin The pin number for the digital output channel 5. + * @param do6_pin The pin number for the digital output channel 6. + * @param do7_pin The pin number for the digital output channel 7. + * @param latch_pin The pin number for the latch mode control. */ DigitalOutputsClass(PinName do0_pin = PI_6, PinName do1_pin = PH_9, @@ -37,51 +47,53 @@ class DigitalOutputsClass { ~DigitalOutputsClass(); /** - * @brief Initialize the - * - * @return true If the X is successfully initialized, false Otherwise + * @brief Initialize the DigitalOutputs module with the specified latch mode. + * + * @param latch_mode The latch mode for thermal shutdown. If true, thermal shutdown operates in the latch mode. Otherwise, it operates in the auto-retry mode. + * @return true If the DigitalOutputs module is successfully initialized, false Otherwise */ - bool begin(); + bool begin(bool latch_mode = true); /** - * @brief Set a particular digital output - * - * @param index digital output to be set - * @param val set value (HIGH/LOW) + * @brief Write the output value for the given channel. + * + * @param channel The channel number to write to. + * @param val The value to write. It can be either PinStatus::HIGH or PinStatus::LOW. */ void write(uint8_t channel, PinStatus val); /** - * @brief Set all digital outputs at the same time. - * - * @param val 8 bit integer to set all 8 channels. e.g: - * Set all to HIGH -> val = 255 (0b11111111) - * Set all to LOW -> val = 0 (0b00000000) + * @brief Set the state of all digital outputs simultaneously. + * + * @param val_mask An 8-bit integer representing the state of all 8 channels. Each bit corresponds to a channel, where 1 represents HIGH and 0 represents LOW. + * For example: + * - To set all channels to HIGH: val_mask = 255 (0b11111111) + * - To set all channels to LOW: val_mask = 0 (0b00000000) */ - void writeAll(uint8_t val); + void writeAll(uint8_t val_mask); +private: + PinName _do0; + PinName _do1; + PinName _do2; + PinName _do3; + PinName _do4; + PinName _do5; + PinName _do6; + PinName _do7; + PinName _latch; /** * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. * The output latches off when thermal shutdown occurs. */ - void setLatch(); + void _setLatchMode(); /** * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) * to avoid repetitive thermal shutdown. */ - void setRetry(); -private: - PinName _do0; - PinName _do1; - PinName _do2; - PinName _do3; - PinName _do4; - PinName _do5; - PinName _do6; - PinName _do7; - PinName _latch; + void _setAutoRetryMode(); }; extern DigitalOutputsClass MachineControl_DigitalOutputs; From 0acb433239146f4d87705add6df126710e7dda4e Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 13 Jul 2023 16:36:24 +0200 Subject: [PATCH 08/47] create ProgrammableDIOClass as separate module --- src/Arduino_MachineControl.h | 48 +----------------------------------- src/Objects.cpp | 1 - src/ProgrammableDIOClass.cpp | 15 +++++++++++ src/ProgrammableDIOClass.h | 43 ++++++++++++++++++++++++++++++++ 4 files changed, 59 insertions(+), 48 deletions(-) create mode 100644 src/ProgrammableDIOClass.cpp create mode 100644 src/ProgrammableDIOClass.h diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index 1ea97c0..074f17e 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -16,6 +16,7 @@ #include "AnalogInClass.h" #include "AnalogOutClass.h" #include "DigitalOutputsClass.h" +#include "ProgrammableDIOClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -211,53 +212,6 @@ class EncoderClass { extern EncoderClass encoders; -/* - using gpio expander class https://www.i2cdevlib.com/devices/tca6424a#source - Ask Giampaolo for proper porting - Expander interrupt is PI_5 - prog_latch_retry (AKA TERM ? ) is PH_14 - - TODO: check if Wire and address are correct -*/ - - -/** - * The ProgrammableDIOClass is used to initialize the IOExpanders and configure the - * thermal shutdown mode of the high side switches. - */ -class ProgrammableDIOClass : public ArduinoIOExpanderClass { -public: - - /** - * Test connection with the IOExpander and set all the pins to the default mode. - * @return true if OK, false if fault - */ - bool init() { - return begin(IO_ADD); - } - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. - * The output latches off when thermal shutdown occurs. - */ - void setLatch() { - prog_latch_retry = 0; - } - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. - * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) - * to avoid repetitive thermal shutdown. - */ - void setRetry() { - prog_latch_retry = 1; - } -private: - mbed::DigitalOut prog_latch_retry = mbed::DigitalOut(PH_14); -}; - -extern ProgrammableDIOClass digital_programmables; - class ProgrammableDINClass : public ArduinoIOExpanderClass { public: /** diff --git a/src/Objects.cpp b/src/Objects.cpp index cc7ff8a..072f393 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -5,7 +5,6 @@ RTDClass temp_probes; COMMClass comm_protocols; EncoderClass encoders; ProgrammableDINClass digital_inputs; -ProgrammableDIOClass digital_programmables; RtcControllerClass rtc_controller; USBClass usb_controller; } diff --git a/src/ProgrammableDIOClass.cpp b/src/ProgrammableDIOClass.cpp new file mode 100644 index 0000000..4e44c6f --- /dev/null +++ b/src/ProgrammableDIOClass.cpp @@ -0,0 +1,15 @@ +#include "ProgrammableDIOClass.h" + +bool ProgrammableDIOClass::init() { + return begin(IO_ADD); +} + +void ProgrammableDIOClass::setLatch() { + prog_latch_retry = 0; +} + +void ProgrammableDIOClass::setRetry() { + prog_latch_retry = 1; +} + +ProgrammableDIOClass digital_programmables; \ No newline at end of file diff --git a/src/ProgrammableDIOClass.h b/src/ProgrammableDIOClass.h new file mode 100644 index 0000000..ea5c8a7 --- /dev/null +++ b/src/ProgrammableDIOClass.h @@ -0,0 +1,43 @@ +/* + using gpio expander class https://www.i2cdevlib.com/devices/tca6424a#source + Ask Giampaolo for proper porting + Expander interrupt is PI_5 + prog_latch_retry (AKA TERM ? ) is PH_14 + + TODO: check if Wire and address are correct +*/ + +#include "utility/ioexpander/ArduinoIOExpander.h" +#include +#include + +/** + * The ProgrammableDIOClass is used to initialize the IOExpanders and configure the + * thermal shutdown mode of the high side switches. + */ +class ProgrammableDIOClass : public ArduinoIOExpanderClass { +public: + + /** + * Test connection with the IOExpander and set all the pins to the default mode. + * @return true if OK, false if fault + */ + bool init(); + + /** + * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. + * The output latches off when thermal shutdown occurs. + */ + void setLatch(); + + /** + * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. + * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) + * to avoid repetitive thermal shutdown. + */ + void setRetry(); +private: + mbed::DigitalOut prog_latch_retry = mbed::DigitalOut(PH_14); +}; + +extern ProgrammableDIOClass digital_programmables; \ No newline at end of file From bfec7b7ac5ad6c1eb6632e0d98a08c34267880f9 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 12:45:55 +0200 Subject: [PATCH 09/47] ProgrammableDIO class refactoring --- .../CombinedIOExpander/CombinedIOExpander.ino | 24 +++--- .../GPIO_programmable/GPIO_programmable.ino | 19 +++-- src/ProgrammableDIOClass.cpp | 40 ++++++++-- src/ProgrammableDIOClass.h | 79 ++++++++++++------- 4 files changed, 102 insertions(+), 60 deletions(-) diff --git a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino b/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino index 9615050..d0ac7e3 100644 --- a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino +++ b/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino @@ -21,26 +21,22 @@ void setup() { Serial.begin(9600); while (!Serial); Wire.begin(); + if (!digital_inputs.init()){ Serial.println("GPIO expander initialization fail!!"); - } - if (!digital_programmables.init()){ + } + if (!MachineControl_DigitalProgrammables.begin()){ Serial.println("GPIO expander initialization fail!!"); - } - - Serial.println("GPIO expander initialization done"); - digital_programmables.setLatch(); - Serial.println("GPIO expander initialization done"); -// digital_inputs.setLatch(); + } } void loop() { // Write the status value to On to Pin 3 - digital_programmables.set(IO_WRITE_CH_PIN_03, SWITCH_ON); + MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_ON); delay(1000); // Read from PROGRAMMABLE DIGITAL I/O Pin 3 - Serial.println("Read IO Pin 03: " + String(digital_programmables.read(IO_READ_CH_PIN_03))); + Serial.println("Read IO Pin 03: " + String(MachineControl_DigitalProgrammables.read(IO_READ_CH_PIN_03))); delay(1000); // Read from DIGITAL INPUT Expander Pin 3 @@ -48,19 +44,19 @@ void loop() { delay(1000); // Write the status value to Off to Pin 3 - digital_programmables.set(IO_WRITE_CH_PIN_03, SWITCH_OFF); + MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_OFF); delay(1000); Serial.println(); // Write the status value to On to all the Output Pins - digital_programmables.writeAll(SWITCH_ON_ALL); + MachineControl_DigitalProgrammables.writeAll(SWITCH_ON_ALL); // Reads from all Input Pins readAll(); delay(1000); // Write the status value to Off all to all the Output Pins - digital_programmables.writeAll(SWITCH_OFF_ALL); + MachineControl_DigitalProgrammables.writeAll(SWITCH_OFF_ALL); // Reads from all Input Pins readAll(); @@ -71,7 +67,7 @@ void loop() { void readAll() { - uint32_t inputs = digital_programmables.readAll(); + uint32_t inputs = MachineControl_DigitalProgrammables.readAll(); Serial.println("CH00: " + String((inputs & (1 << IO_READ_CH_PIN_00)) >> IO_READ_CH_PIN_00)); Serial.println("CH01: " + String((inputs & (1 << IO_READ_CH_PIN_01)) >> IO_READ_CH_PIN_01)); Serial.println("CH02: " + String((inputs & (1 << IO_READ_CH_PIN_02)) >> IO_READ_CH_PIN_02)); diff --git a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino index cf80f0a..e8711f2 100644 --- a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino +++ b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino @@ -21,47 +21,46 @@ void setup() { Serial.begin(9600); while (!Serial); Wire.begin(); - if (!digital_programmables.init()) { + if (!MachineControl_DigitalProgrammables.begin()) { Serial.println("GPIO expander initialization fail!!"); } Serial.println("GPIO expander initialization done"); - digital_programmables.setLatch(); } void loop() { // Write the status value to On to Pin 3 - digital_programmables.set(IO_WRITE_CH_PIN_03, SWITCH_ON); + MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_ON); delay(1000); // Read from Pin 3 - Serial.println("Read Pin 03: " + String(digital_programmables.read(IO_READ_CH_PIN_03))); + Serial.println("Read Pin 03: " + String(MachineControl_DigitalProgrammables.read(IO_READ_CH_PIN_03))); delay(1000); // Write the status value to Off to Pin 3 - digital_programmables.set(IO_WRITE_CH_PIN_03, SWITCH_OFF); + MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_OFF); delay(1000); Serial.println(); // Sets all the status Pins Values to On in one single operation uint32_t status = ON_VALUE_PIN_10 | ON_VALUE_PIN_08 | ON_VALUE_PIN_06 | ON_VALUE_PIN_04 | ON_VALUE_PIN_02 | ON_VALUE_PIN_00; - digital_programmables.writeAll(status); + MachineControl_DigitalProgrammables.writeAll(status); delay(1000); // Toggles the actual status values of all digital programmables Pins - digital_programmables.toggle(); + MachineControl_DigitalProgrammables.toggle(); delay(1000); Serial.println(); // Write the status value to On to all the Output Pins - digital_programmables.writeAll(SWITCH_ON_ALL); + MachineControl_DigitalProgrammables.writeAll(SWITCH_ON_ALL); // Reads from all Input Pins readAll(); delay(1000); // Write the status value to Off all to all the Output Pins - digital_programmables.writeAll(SWITCH_OFF_ALL); + MachineControl_DigitalProgrammables.writeAll(SWITCH_OFF_ALL); // Reads from all Input Pins readAll(); @@ -70,7 +69,7 @@ void loop() { } uint8_t readAll() { - uint32_t inputs = digital_programmables.readAll(); + uint32_t inputs = MachineControl_DigitalProgrammables.readAll(); Serial.println("CH00: " + String((inputs & (1 << IO_READ_CH_PIN_00)) >> IO_READ_CH_PIN_00)); Serial.println("CH01: " + String((inputs & (1 << IO_READ_CH_PIN_01)) >> IO_READ_CH_PIN_01)); Serial.println("CH02: " + String((inputs & (1 << IO_READ_CH_PIN_02)) >> IO_READ_CH_PIN_02)); diff --git a/src/ProgrammableDIOClass.cpp b/src/ProgrammableDIOClass.cpp index 4e44c6f..ad64d99 100644 --- a/src/ProgrammableDIOClass.cpp +++ b/src/ProgrammableDIOClass.cpp @@ -1,15 +1,41 @@ +/** + * @file ProgrammableDIOClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Programmable Digital IO connector of the Portenta Machine Control library. + */ + +/* Includes -----------------------------------------------------------------*/ #include "ProgrammableDIOClass.h" -bool ProgrammableDIOClass::init() { - return begin(IO_ADD); +/* Functions -----------------------------------------------------------------*/ +ProgrammableDIOClass::ProgrammableDIOClass(PinName latch_pin) +: _latch{latch_pin} +{ } + +ProgrammableDIOClass::~ProgrammableDIOClass() +{ } + +bool ProgrammableDIOClass::begin(bool latch_mode) { + ArduinoIOExpanderClass::begin(IO_ADD); + + pinMode(_latch, OUTPUT); + + if(latch_mode) { + _setLatchMode(); + } else { + _setAutoRetryMode(); + } + + return true; } -void ProgrammableDIOClass::setLatch() { - prog_latch_retry = 0; +void ProgrammableDIOClass::_setLatchMode() { + digitalWrite(_latch, HIGH); } -void ProgrammableDIOClass::setRetry() { - prog_latch_retry = 1; +void ProgrammableDIOClass::_setAutoRetryMode() { + digitalWrite(_latch, LOW); } -ProgrammableDIOClass digital_programmables; \ No newline at end of file +ProgrammableDIOClass MachineControl_DigitalProgrammables; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/ProgrammableDIOClass.h b/src/ProgrammableDIOClass.h index ea5c8a7..987fab0 100644 --- a/src/ProgrammableDIOClass.h +++ b/src/ProgrammableDIOClass.h @@ -1,43 +1,64 @@ -/* - using gpio expander class https://www.i2cdevlib.com/devices/tca6424a#source - Ask Giampaolo for proper porting - Expander interrupt is PI_5 - prog_latch_retry (AKA TERM ? ) is PH_14 +/** + * @file ProgrammableDIOClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Programmable Digital IO connector of the Portenta Machine Control library. + * + * This library allows interfacing with the IO Expander and configuring the thermal shutdown mode of the high-side switches. + */ - TODO: check if Wire and address are correct -*/ +#ifndef __PROGRAMMABLE_DIO_CLASS_H +#define __PROGRAMMABLE_DIO_CLASS_H +/* Includes -------------------------------------------------------------------*/ #include "utility/ioexpander/ArduinoIOExpander.h" #include #include +/* Class ----------------------------------------------------------------------*/ + /** - * The ProgrammableDIOClass is used to initialize the IOExpanders and configure the - * thermal shutdown mode of the high side switches. + * @class ProgrammableDIOClass + * @brief Class for the Programmable Digital IO connector of the Portenta Machine Control. + * + * This class extends the ArduinoIOExpanderClass to interface with the IO Expander and provides methods to configure thermal shutdown modes. */ class ProgrammableDIOClass : public ArduinoIOExpanderClass { public: + /** + * @brief Construct a ProgrammableDIOClass object. + * + * This constructor initializes a ProgrammableDIOClass object with the specified pin assignment for the latch pin. + * + * @param latch_pin The pin number for the latch mode control. + */ + ProgrammableDIOClass(PinName latch_pin = PH_14); + ~ProgrammableDIOClass(); + + /** + * @brief Initialize the ProgrammableDIO module with the specified latch mode. + * + * @param latch_mode The latch mode for thermal shutdown. If true, thermal shutdown operates in the latch mode. Otherwise, it operates in the auto-retry mode. + * @return true If the ProgrammableDIO module is successfully initialized, false otherwise. + */ + bool begin(bool latch_mode = true); - /** - * Test connection with the IOExpander and set all the pins to the default mode. - * @return true if OK, false if fault - */ - bool init(); - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. - * The output latches off when thermal shutdown occurs. - */ - void setLatch(); - - /** - * Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. - * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) - * to avoid repetitive thermal shutdown. - */ - void setRetry(); private: - mbed::DigitalOut prog_latch_retry = mbed::DigitalOut(PH_14); + PinName _latch; + + /** + * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. + * The output latches off when thermal shutdown occurs. + */ + void _setLatchMode(); + + /** + * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in auto-retry mode. + * The output automatically recovers when TJ < T(SD) – T(hys), but the current is limited to ICL(TSD) + * to avoid repetitive thermal shutdown. + */ + void _setAutoRetryMode(); }; -extern ProgrammableDIOClass digital_programmables; \ No newline at end of file +extern ProgrammableDIOClass MachineControl_DigitalProgrammables; + +#endif /* __PROGRAMMABLE_DIO_CLASS_H */ \ No newline at end of file From 321919b3e3dc7d8a54f3bc27468e66caae7a0b45 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 12:51:07 +0200 Subject: [PATCH 10/47] create rogrammableDINClass as separate module --- src/Arduino_MachineControl.h | 14 +------------- src/Objects.cpp | 1 - src/ProgrammableDINClass.cpp | 7 +++++++ src/ProgrammableDINClass.h | 14 ++++++++++++++ 4 files changed, 22 insertions(+), 14 deletions(-) create mode 100644 src/ProgrammableDINClass.cpp create mode 100644 src/ProgrammableDINClass.h diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index 074f17e..bb56a32 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -17,6 +17,7 @@ #include "AnalogOutClass.h" #include "DigitalOutputsClass.h" #include "ProgrammableDIOClass.h" +#include "ProgrammableDINClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -212,19 +213,6 @@ class EncoderClass { extern EncoderClass encoders; -class ProgrammableDINClass : public ArduinoIOExpanderClass { -public: - /** - * Test connection with the IOExpander and set all the pins to the default mode. - * @return true if OK, false if fault - */ - bool init() { - return begin(DIN_ADD); - } -}; - -extern ProgrammableDINClass digital_inputs; - /** * The RtcControllerClass is a wrapper for the PCF8563TClass() that is used to * set and get the time to/from the PCF8563T RTC. diff --git a/src/Objects.cpp b/src/Objects.cpp index 072f393..237e334 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -4,7 +4,6 @@ namespace machinecontrol { RTDClass temp_probes; COMMClass comm_protocols; EncoderClass encoders; -ProgrammableDINClass digital_inputs; RtcControllerClass rtc_controller; USBClass usb_controller; } diff --git a/src/ProgrammableDINClass.cpp b/src/ProgrammableDINClass.cpp new file mode 100644 index 0000000..46aa28c --- /dev/null +++ b/src/ProgrammableDINClass.cpp @@ -0,0 +1,7 @@ +#include "ProgrammableDINClass.h" + +bool ProgrammableDINClass::init() { + return begin(DIN_ADD); +} + +ProgrammableDINClass digital_inputs; \ No newline at end of file diff --git a/src/ProgrammableDINClass.h b/src/ProgrammableDINClass.h new file mode 100644 index 0000000..2aae55f --- /dev/null +++ b/src/ProgrammableDINClass.h @@ -0,0 +1,14 @@ +#include "utility/ioexpander/ArduinoIOExpander.h" +#include +#include + +class ProgrammableDINClass : public ArduinoIOExpanderClass { +public: + /** + * Test connection with the IOExpander and set all the pins to the default mode. + * @return true if OK, false if fault + */ + bool init(); +}; + +extern ProgrammableDINClass digital_inputs; \ No newline at end of file From 65a8eafea9879af62e109c3a03110a8f4ecd009a Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 15:21:37 +0200 Subject: [PATCH 11/47] ProgrammableDIN class refactoring --- .../CombinedIOExpander/CombinedIOExpander.ino | 7 ++- .../Digital_input/Digital_input.ino | 23 +++++----- .../GPIO_programmable/GPIO_programmable.ino | 1 - src/ProgrammableDINClass.cpp | 23 ++++++++-- src/ProgrammableDINClass.h | 43 ++++++++++++++++--- 5 files changed, 71 insertions(+), 26 deletions(-) diff --git a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino b/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino index d0ac7e3..8a6dc98 100644 --- a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino +++ b/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino @@ -15,14 +15,13 @@ #include #include "Wire.h" -using namespace machinecontrol; void setup() { Serial.begin(9600); while (!Serial); Wire.begin(); - if (!digital_inputs.init()){ + if (!MachineControl_DigitalInputs.begin()){ Serial.println("GPIO expander initialization fail!!"); } if (!MachineControl_DigitalProgrammables.begin()){ @@ -40,7 +39,7 @@ void loop() { delay(1000); // Read from DIGITAL INPUT Expander Pin 3 - Serial.println("Read DIN Pin 03: " + String(digital_inputs.read(DIN_READ_CH_PIN_03))); + Serial.println("Read DIN Pin 03: " + String(MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_03))); delay(1000); // Write the status value to Off to Pin 3 @@ -81,7 +80,7 @@ void readAll() { Serial.println("CH10: " + String((inputs & (1 << IO_READ_CH_PIN_10)) >> IO_READ_CH_PIN_10)); Serial.println("CH11: " + String((inputs & (1 << IO_READ_CH_PIN_11)) >> IO_READ_CH_PIN_11)); Serial.println(); - inputs = digital_inputs.readAll(); + inputs = MachineControl_DigitalInputs.readAll(); Serial.println("CH00: " + String((inputs & (1 << DIN_READ_CH_PIN_00)) >> DIN_READ_CH_PIN_00)); Serial.println("CH01: " + String((inputs & (1 << DIN_READ_CH_PIN_01)) >> DIN_READ_CH_PIN_01)); Serial.println("CH02: " + String((inputs & (1 << DIN_READ_CH_PIN_02)) >> DIN_READ_CH_PIN_02)); diff --git a/examples/Digital_programmable/Digital_input/Digital_input.ino b/examples/Digital_programmable/Digital_input/Digital_input.ino index 91c0f7d..eccfcef 100644 --- a/examples/Digital_programmable/Digital_input/Digital_input.ino +++ b/examples/Digital_programmable/Digital_input/Digital_input.ino @@ -13,8 +13,7 @@ #include #include "Wire.h" -using namespace machinecontrol; - uint16_t readings = 0; +uint16_t readings = 0; void setup() { Serial.begin(9600); @@ -22,7 +21,7 @@ void setup() { while(!Serial); Wire.begin(); - if (!digital_inputs.init()) { + if (!MachineControl_DigitalInputs.begin()) { Serial.println("Digital input GPIO expander initialization fail!!"); } } @@ -32,28 +31,28 @@ void loop() { readAll(); //Read one-by-one each channel and print them one-by-one - readings = digital_inputs.read(DIN_READ_CH_PIN_00); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_00); Serial.println("CH00: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_01); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_01); Serial.println("CH01: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_02); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_02); Serial.println("CH02: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_03); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_03); Serial.println("CH03: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_04); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_04); Serial.println("CH04: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_05); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_05); Serial.println("CH05: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_06); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_06); Serial.println("CH06: "+String(readings)); - readings = digital_inputs.read(DIN_READ_CH_PIN_07); + readings = MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_07); Serial.println("CH07: "+String(readings)); Serial.println(); @@ -62,7 +61,7 @@ void loop() { } uint8_t readAll() { - uint32_t inputs = digital_inputs.readAll(); + uint32_t inputs = MachineControl_DigitalInputs.readAll(); Serial.println("CH00: " + String((inputs & (1 << DIN_READ_CH_PIN_00)) >> DIN_READ_CH_PIN_00)); Serial.println("CH01: " + String((inputs & (1 << DIN_READ_CH_PIN_01)) >> DIN_READ_CH_PIN_01)); Serial.println("CH02: " + String((inputs & (1 << DIN_READ_CH_PIN_02)) >> DIN_READ_CH_PIN_02)); diff --git a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino index e8711f2..26db172 100644 --- a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino +++ b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino @@ -15,7 +15,6 @@ #include #include "Wire.h" -using namespace machinecontrol; void setup() { Serial.begin(9600); diff --git a/src/ProgrammableDINClass.cpp b/src/ProgrammableDINClass.cpp index 46aa28c..a27e6d8 100644 --- a/src/ProgrammableDINClass.cpp +++ b/src/ProgrammableDINClass.cpp @@ -1,7 +1,24 @@ +/** + * @file ProgrammableDINClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Programmable Digital Input connector of the Portenta Machine Control library. + */ + +/* Includes -----------------------------------------------------------------*/ #include "ProgrammableDINClass.h" -bool ProgrammableDINClass::init() { - return begin(DIN_ADD); +/* Functions -----------------------------------------------------------------*/ +ProgrammableDINClass::ProgrammableDINClass() +{ } + +ProgrammableDINClass::~ProgrammableDINClass() +{ } + +bool ProgrammableDINClass::begin() { + ArduinoIOExpanderClass::begin(DIN_ADD); + + return true; } -ProgrammableDINClass digital_inputs; \ No newline at end of file +ProgrammableDINClass MachineControl_DigitalInputs; +/**** END OF FILE ****/ diff --git a/src/ProgrammableDINClass.h b/src/ProgrammableDINClass.h index 2aae55f..84cc981 100644 --- a/src/ProgrammableDINClass.h +++ b/src/ProgrammableDINClass.h @@ -1,14 +1,45 @@ +/** + * @file ProgrammableDINClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Programmable Digital Input connector of the Portenta Machine Control library. + * + * This library allows interfacing with the IO Expander and configuring the digital inputs. + */ + +#ifndef __PROGRAMMABLE_DIN_CLASS_H +#define __PROGRAMMABLE_DIN_CLASS_H + +/* Includes -------------------------------------------------------------------*/ #include "utility/ioexpander/ArduinoIOExpander.h" #include #include +/* Class ----------------------------------------------------------------------*/ + +/** + * @class ProgrammableDINClass + * @brief Class for the Programmable Digital Input connector of the Portenta Machine Control. + * + * This class extends the ArduinoIOExpanderClass to interface with the IO Expander and provides methods to configure digital inputs. + */ class ProgrammableDINClass : public ArduinoIOExpanderClass { public: - /** - * Test connection with the IOExpander and set all the pins to the default mode. - * @return true if OK, false if fault - */ - bool init(); + /** + * @brief Construct a ProgrammableDINClass object. + */ + ProgrammableDINClass(); + ~ProgrammableDINClass(); + + /** + * @brief Initialize the ProgrammableDIN module. + * + * Test connection with the IOExpander and set all the pins to the default mode. + * + * @return true If the ProgrammableDIN module is successfully initialized, false otherwise. + */ + bool begin(); }; -extern ProgrammableDINClass digital_inputs; \ No newline at end of file +extern ProgrammableDINClass MachineControl_DigitalInputs; + +#endif /* __PROGRAMMABLE_DIN_CLASS_H */ \ No newline at end of file From e5dda7d4358e3cfdbae7b87b574e6f2891e50066 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 16:40:54 +0200 Subject: [PATCH 12/47] create RTDClass as separate module --- examples/Temp_probes_RTD/Temp_probes_RTD.ino | 2 - .../Temp_probes_Thermocouples.ino | 2 - src/Arduino_MachineControl.h | 87 +------------------ src/RTDClass.cpp | 54 ++++++++++++ src/RTDClass.h | 46 ++++++++++ 5 files changed, 101 insertions(+), 90 deletions(-) create mode 100644 src/RTDClass.cpp create mode 100644 src/RTDClass.h diff --git a/examples/Temp_probes_RTD/Temp_probes_RTD.ino b/examples/Temp_probes_RTD/Temp_probes_RTD.ino index 2899dc6..fcbce7d 100644 --- a/examples/Temp_probes_RTD/Temp_probes_RTD.ino +++ b/examples/Temp_probes_RTD/Temp_probes_RTD.ino @@ -16,8 +16,6 @@ #include -using namespace machinecontrol; - // The value of the Rref resistor. Use 430.0 for PT100 and 4300.0 for PT1000 #define RREF 400.0 // The 'nominal' 0-degrees-C resistance of the sensor diff --git a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino index 5fef867..14d950c 100644 --- a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino +++ b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino @@ -18,8 +18,6 @@ #include -using namespace machinecontrol; - void setup() { Serial.begin(9600); // Initialize temperature probes diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index bb56a32..ccddc27 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -18,95 +18,10 @@ #include "DigitalOutputsClass.h" #include "ProgrammableDIOClass.h" #include "ProgrammableDINClass.h" - -#if __has_include("portenta_info.h") -#include "portenta_info.h" -#define TRY_REV2_RECOGNITION -uint8_t* boardInfo(); -#define PMC_R2_SKU (24 << 8 | 3) -#endif +#include "RTDClass.h" namespace machinecontrol { -/** - * The RTDClass allows enabling and selecting the different temperature sensor inputs - * (RTD and thermocouples) - */ -class RTDClass { -public: - - /** - * Select the input channel to be read (3 channels available) - * - * @param channel (0-2) - */ - void selectChannel(int channel) { - -#ifdef TRY_REV2_RECOGNITION - // check if OTP data is present AND the board is mounted on a r2 carrier - auto info = (PortentaBoardInfo*)boardInfo(); - if (info->magic == 0xB5 && info->carrier == PMC_R2_SKU) { - // reverse channels 0 and 2 - switch (channel) { - case 0: - channel = 2; - break; - case 2: - channel = 0; - break; - default: - break; - } - } -#endif -#undef TRY_REV2_RECOGNITION - - for (int i=0; i<3; i++) { - ch_sel[i] = (i == channel ? 1 : 0); - } - delay(150); - } - - /** - * Enable the CS of the Thermocouple to digital converter - * Disable the CS for the RTD to digital converter - */ - void enableTC() { - rtd_th = 0; - digitalWrite(PI_0, LOW); - digitalWrite(PA_6, HIGH); - } - - /** - * Enable the CS of the RDT to digital converter. - * Disable the CS of the Thermocouple to digital converter - */ - void enableRTD() { - rtd_th = 1; - digitalWrite(PI_0, HIGH); - digitalWrite(PA_6, LOW); - - } - - /** - * Disable Chip select for both RTD and thermocouple digital converters. - * - */ - void disableCS() { - digitalWrite(PI_0, HIGH); - digitalWrite(PA_6, HIGH); - } - MAX31865Class rtd = MAX31865Class(PA_6); - MAX31855Class tc = MAX31855Class(7); - -private: - mbed::DigitalOut ch_sel[3] = { mbed::DigitalOut(PD_6), mbed::DigitalOut(PI_4), mbed::DigitalOut(PG_10)}; - mbed::DigitalOut rtd_th = mbed::DigitalOut(PC_15); - -}; - -extern RTDClass temp_probes; - /** * The COMMClass is used to initialize the CAN and RS485 LEDs and * establish the power mode of the CAN bus. diff --git a/src/RTDClass.cpp b/src/RTDClass.cpp new file mode 100644 index 0000000..20f9ab2 --- /dev/null +++ b/src/RTDClass.cpp @@ -0,0 +1,54 @@ +#include "RTDClass.h" + +#if __has_include("portenta_info.h") +#include "portenta_info.h" +#define TRY_REV2_RECOGNITION +uint8_t* boardInfo(); +#define PMC_R2_SKU (24 << 8 | 3) +#endif + +void RTDClass::selectChannel(int channel) { + +#ifdef TRY_REV2_RECOGNITION + // check if OTP data is present AND the board is mounted on a r2 carrier + auto info = (PortentaBoardInfo*)boardInfo(); + if (info->magic == 0xB5 && info->carrier == PMC_R2_SKU) { + // reverse channels 0 and 2 + switch (channel) { + case 0: + channel = 2; + break; + case 2: + channel = 0; + break; + default: + break; + } + } +#endif +#undef TRY_REV2_RECOGNITION + + for (int i=0; i<3; i++) { + ch_sel[i] = (i == channel ? 1 : 0); + } + delay(150); +} + +void RTDClass::enableTC() { + rtd_th = 0; + digitalWrite(PI_0, LOW); + digitalWrite(PA_6, HIGH); +} + +void RTDClass::enableRTD() { + rtd_th = 1; + digitalWrite(PI_0, HIGH); + digitalWrite(PA_6, LOW); +} + +void RTDClass::disableCS() { + digitalWrite(PI_0, HIGH); + digitalWrite(PA_6, HIGH); +} + +RTDClass temp_probes; \ No newline at end of file diff --git a/src/RTDClass.h b/src/RTDClass.h new file mode 100644 index 0000000..6bf1d79 --- /dev/null +++ b/src/RTDClass.h @@ -0,0 +1,46 @@ +#include "utility/MAX31865/MAX31865.h" +#include "utility/THERMOCOUPLE/MAX31855.h" +#include +#include + +/** + * The RTDClass allows enabling and selecting the different temperature sensor inputs + * (RTD and thermocouples) + */ +class RTDClass { +public: + + /** + * Select the input channel to be read (3 channels available) + * + * @param channel (0-2) + */ + void selectChannel(int channel); + + /** + * Enable the CS of the Thermocouple to digital converter + * Disable the CS for the RTD to digital converter + */ + void enableTC(); + + /** + * Enable the CS of the RDT to digital converter. + * Disable the CS of the Thermocouple to digital converter + */ + void enableRTD(); + + /** + * Disable Chip select for both RTD and thermocouple digital converters. + * + */ + void disableCS(); + + MAX31865Class rtd = MAX31865Class(PA_6); + MAX31855Class tc = MAX31855Class(7); +private: + mbed::DigitalOut ch_sel[3] = { mbed::DigitalOut(PD_6), mbed::DigitalOut(PI_4), mbed::DigitalOut(PG_10)}; + mbed::DigitalOut rtd_th = mbed::DigitalOut(PC_15); + +}; + +extern RTDClass temp_probes; \ No newline at end of file From e6513753840b86b7de7dcd61b740be584ddab986 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 16:47:37 +0200 Subject: [PATCH 13/47] Class renaming: RTDClass -> TempProbesClass --- src/Arduino_MachineControl.h | 2 +- src/Objects.cpp | 1 - src/{RTDClass.cpp => TempProbesClass.cpp} | 12 ++++++------ src/{RTDClass.h => TempProbesClass.h} | 7 +++---- 4 files changed, 10 insertions(+), 12 deletions(-) rename src/{RTDClass.cpp => TempProbesClass.cpp} (82%) rename src/{RTDClass.h => TempProbesClass.h} (86%) diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index ccddc27..bc8dbf4 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -18,7 +18,7 @@ #include "DigitalOutputsClass.h" #include "ProgrammableDIOClass.h" #include "ProgrammableDINClass.h" -#include "RTDClass.h" +#include "TempProbesClass.h" namespace machinecontrol { diff --git a/src/Objects.cpp b/src/Objects.cpp index 237e334..69054e4 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -1,7 +1,6 @@ #include "Arduino_MachineControl.h" namespace machinecontrol { -RTDClass temp_probes; COMMClass comm_protocols; EncoderClass encoders; RtcControllerClass rtc_controller; diff --git a/src/RTDClass.cpp b/src/TempProbesClass.cpp similarity index 82% rename from src/RTDClass.cpp rename to src/TempProbesClass.cpp index 20f9ab2..a801968 100644 --- a/src/RTDClass.cpp +++ b/src/TempProbesClass.cpp @@ -1,4 +1,4 @@ -#include "RTDClass.h" +#include "TempProbesClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -7,7 +7,7 @@ uint8_t* boardInfo(); #define PMC_R2_SKU (24 << 8 | 3) #endif -void RTDClass::selectChannel(int channel) { +void TempProbesClass::selectChannel(int channel) { #ifdef TRY_REV2_RECOGNITION // check if OTP data is present AND the board is mounted on a r2 carrier @@ -34,21 +34,21 @@ void RTDClass::selectChannel(int channel) { delay(150); } -void RTDClass::enableTC() { +void TempProbesClass::enableTC() { rtd_th = 0; digitalWrite(PI_0, LOW); digitalWrite(PA_6, HIGH); } -void RTDClass::enableRTD() { +void TempProbesClass::enableRTD() { rtd_th = 1; digitalWrite(PI_0, HIGH); digitalWrite(PA_6, LOW); } -void RTDClass::disableCS() { +void TempProbesClass::disableCS() { digitalWrite(PI_0, HIGH); digitalWrite(PA_6, HIGH); } -RTDClass temp_probes; \ No newline at end of file +TempProbesClass temp_probes; \ No newline at end of file diff --git a/src/RTDClass.h b/src/TempProbesClass.h similarity index 86% rename from src/RTDClass.h rename to src/TempProbesClass.h index 6bf1d79..7e6c02a 100644 --- a/src/RTDClass.h +++ b/src/TempProbesClass.h @@ -4,10 +4,10 @@ #include /** - * The RTDClass allows enabling and selecting the different temperature sensor inputs + * The TempProbesClass allows enabling and selecting the different temperature sensor inputs * (RTD and thermocouples) */ -class RTDClass { +class TempProbesClass { public: /** @@ -40,7 +40,6 @@ class RTDClass { private: mbed::DigitalOut ch_sel[3] = { mbed::DigitalOut(PD_6), mbed::DigitalOut(PI_4), mbed::DigitalOut(PG_10)}; mbed::DigitalOut rtd_th = mbed::DigitalOut(PC_15); - }; -extern RTDClass temp_probes; \ No newline at end of file +extern TempProbesClass temp_probes; \ No newline at end of file From 478437fc1174a10fba4df3aad1895570a3c3b017 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 25 Jul 2023 18:46:38 +0200 Subject: [PATCH 14/47] TempProbes class refactoring --- examples/Temp_probes_RTD/Temp_probes_RTD.ino | 69 +++++------ .../Temp_probes_Thermocouples.ino | 17 ++- src/TempProbesClass.cpp | 89 ++++++++++++-- src/TempProbesClass.h | 116 +++++++++++++----- 4 files changed, 205 insertions(+), 86 deletions(-) diff --git a/examples/Temp_probes_RTD/Temp_probes_RTD.ino b/examples/Temp_probes_RTD/Temp_probes_RTD.ino index fcbce7d..cbf132b 100644 --- a/examples/Temp_probes_RTD/Temp_probes_RTD.ino +++ b/examples/Temp_probes_RTD/Temp_probes_RTD.ino @@ -25,121 +25,120 @@ void setup() { Serial.begin(9600); Serial.println("MAX31865 PT100 Sensor Test!"); - temp_probes.rtd.begin(THREE_WIRE); - temp_probes.enableRTD(); + MachineControl_TempProbes.begin(TEMPPROBE_RTD, THREE_WIRE); } void loop() { - temp_probes.selectChannel(0); + MachineControl_TempProbes.selectChannel(0); Serial.println("CHANNEL 0 SELECTED"); - uint16_t rtd = temp_probes.rtd.readRTD(); + uint16_t rtd = MachineControl_TempProbes.RTD.readRTD(); float ratio = rtd; ratio /= 32768; // Check and print any faults - uint8_t fault = temp_probes.rtd.readFault(); + uint8_t fault = MachineControl_TempProbes.RTD.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (temp_probes.rtd.getHighThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (temp_probes.rtd.getLowThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (temp_probes.rtd.getLowREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (temp_probes.rtd.getHighREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getLowRTDINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getVoltageFault(fault)) { + if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - temp_probes.rtd.clearFault(); + MachineControl_TempProbes.RTD.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(temp_probes.rtd.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(100); - temp_probes.selectChannel(1); + MachineControl_TempProbes.selectChannel(1); Serial.println("CHANNEL 1 SELECTED"); - rtd = temp_probes.rtd.readRTD(); + rtd = MachineControl_TempProbes.RTD.readRTD(); ratio = rtd; ratio /= 32768; // Check and print any faults - fault = temp_probes.rtd.readFault(); + fault = MachineControl_TempProbes.RTD.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (temp_probes.rtd.getHighThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (temp_probes.rtd.getLowThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (temp_probes.rtd.getLowREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (temp_probes.rtd.getHighREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getLowRTDINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getVoltageFault(fault)) { + if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - temp_probes.rtd.clearFault(); + MachineControl_TempProbes.RTD.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(temp_probes.rtd.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(100); - temp_probes.selectChannel(2); + MachineControl_TempProbes.selectChannel(2); Serial.println("CHANNEL 2 SELECTED"); - rtd = temp_probes.rtd.readRTD(); + rtd = MachineControl_TempProbes.RTD.readRTD(); ratio = rtd; ratio /= 32768; // Check and print any faults - fault = temp_probes.rtd.readFault(); + fault = MachineControl_TempProbes.RTD.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (temp_probes.rtd.getHighThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (temp_probes.rtd.getLowThresholdFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (temp_probes.rtd.getLowREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (temp_probes.rtd.getHighREFINFault(fault)) { + if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getLowRTDINFault(fault)) { + if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (temp_probes.rtd.getVoltageFault(fault)) { + if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - temp_probes.rtd.clearFault(); + MachineControl_TempProbes.RTD.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(temp_probes.rtd.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(1000); diff --git a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino index 14d950c..51e999b 100644 --- a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino +++ b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino @@ -21,34 +21,31 @@ void setup() { Serial.begin(9600); // Initialize temperature probes - temp_probes.tc.begin(); + MachineControl_TempProbes.begin(TEMPPROBE_TC); Serial.println("Temperature probes initialization done"); - // Enables Thermocouples chip select - temp_probes.enableTC(); - Serial.println("Thermocouples enabled"); } void loop() { //Set CH0, has internal 150 ms delay - temp_probes.selectChannel(0); + MachineControl_TempProbes.selectChannel(0); //Take CH0 measurement - float temp_ch0 = temp_probes.tc.readTemperature(); + float temp_ch0 = MachineControl_TempProbes.TC.readTemperature(); Serial.print("Temperature CH0 [°C]: "); Serial.print(temp_ch0); Serial.println(); //Set CH1, has internal 150 ms delay - temp_probes.selectChannel(1); + MachineControl_TempProbes.selectChannel(1); //Take CH1 measurement - float temp_ch1 = temp_probes.tc.readTemperature(); + float temp_ch1 = MachineControl_TempProbes.TC.readTemperature(); Serial.print("Temperature CH1 [°C]: "); Serial.print(temp_ch1); Serial.println(); //Set CH2, has internal 150 ms delay - temp_probes.selectChannel(2); + MachineControl_TempProbes.selectChannel(2); //Take CH2 measurement - float temp_ch2 = temp_probes.tc.readTemperature(); + float temp_ch2 = MachineControl_TempProbes.TC.readTemperature(); Serial.print("Temperature CH2 [°C]: "); Serial.print(temp_ch2); Serial.println(); diff --git a/src/TempProbesClass.cpp b/src/TempProbesClass.cpp index a801968..d959df6 100644 --- a/src/TempProbesClass.cpp +++ b/src/TempProbesClass.cpp @@ -1,3 +1,10 @@ +/** + * @file TempProbesClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Temperature Probes connector of the Portenta Machine Control. + */ + +/* Includes -----------------------------------------------------------------*/ #include "TempProbesClass.h" #if __has_include("portenta_info.h") @@ -7,6 +14,45 @@ uint8_t* boardInfo(); #define PMC_R2_SKU (24 << 8 | 3) #endif +/* Functions -----------------------------------------------------------------*/ +TempProbesClass::TempProbesClass(PinName ch_sel0_pin, + PinName ch_sel1_pin, + PinName ch_sel2_pin, + PinName rtd_th_pin) +: _ch_sel0{ch_sel0_pin}, _ch_sel1{ch_sel0_pin}, _ch_sel2{ch_sel2_pin}, _rtd_th{rtd_th_pin} +{ } + +TempProbesClass::~TempProbesClass() +{ } + +bool TempProbesClass::begin(uint8_t tempprobe_type, uint8_t io_address) { + bool status = true; + + switch(tempprobe_type) { + case TEMPPROBE_RTD: + TempProbesClass::RTD.begin(io_address); + _enableRTD(); + break; + case TEMPPROBE_TC: + TempProbesClass::TC.begin(); + _enableTC(); + break; + default: + status = false; + break; + } + + pinMode(_ch_sel0, OUTPUT); + pinMode(_ch_sel1, OUTPUT); + pinMode(_ch_sel2, OUTPUT); + pinMode(_rtd_th, OUTPUT); + + pinMode(PI_0, OUTPUT); + pinMode(PA_6, OUTPUT); + + return status; +} + void TempProbesClass::selectChannel(int channel) { #ifdef TRY_REV2_RECOGNITION @@ -27,28 +73,53 @@ void TempProbesClass::selectChannel(int channel) { } #endif #undef TRY_REV2_RECOGNITION - - for (int i=0; i<3; i++) { - ch_sel[i] = (i == channel ? 1 : 0); + switch(channel) { + case 0: + digitalWrite(_ch_sel0, HIGH); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, LOW); + break; + case 1: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, HIGH); + digitalWrite(_ch_sel2, LOW); + break; + case 2: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, HIGH); + break; + default: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, LOW); + break; } delay(150); } -void TempProbesClass::enableTC() { - rtd_th = 0; +void TempProbesClass::end() { + _disableCS(); +} + +void TempProbesClass::_enableTC() { + digitalWrite(_rtd_th, LOW); + digitalWrite(PI_0, LOW); digitalWrite(PA_6, HIGH); } -void TempProbesClass::enableRTD() { - rtd_th = 1; +void TempProbesClass::_enableRTD() { + digitalWrite(_rtd_th, HIGH); + digitalWrite(PI_0, HIGH); digitalWrite(PA_6, LOW); } -void TempProbesClass::disableCS() { +void TempProbesClass::_disableCS() { digitalWrite(PI_0, HIGH); digitalWrite(PA_6, HIGH); } -TempProbesClass temp_probes; \ No newline at end of file +TempProbesClass MachineControl_TempProbes; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/TempProbesClass.h b/src/TempProbesClass.h index 7e6c02a..54a1c96 100644 --- a/src/TempProbesClass.h +++ b/src/TempProbesClass.h @@ -1,45 +1,97 @@ +/** + * @file TempProbesClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Temperature Probes connector of the Portenta Machine Control. + * + * This library allows interfacing with RTD (Resistance Temperature Detector) and Thermocouple temperature sensors + * using the MAX31865 and MAX31855 digital converters. It provides methods to select the sensor type and input channel, + * enabling and disabling the temperature sensors, and reading temperature values. + */ + +#ifndef __TEMPPROBES_CLASS_H +#define __TEMPPROBES_CLASS_H + +/* Includes -------------------------------------------------------------------*/ #include "utility/MAX31865/MAX31865.h" #include "utility/THERMOCOUPLE/MAX31855.h" #include #include +/* Constants ------------------------------------------------------------------*/ +#define TEMPPROBE_RTD 1 +#define TEMPPROBE_TC 2 + +/* Class ----------------------------------------------------------------------*/ + /** - * The TempProbesClass allows enabling and selecting the different temperature sensor inputs - * (RTD and thermocouples) + * @class TempProbesClass + * @brief Class for managing temperature sensor inputs (RTD and thermocouples) of the Portenta Machine Control. + * + * This class allows interfacing with RTD and thermocouple temperature sensors through the use of the MAX31865 and MAX31855 digital converters. + * It provides methods to configure and read temperature values from the selected input channel. */ class TempProbesClass { public: + /** + * @brief Construct a TempProbesClass object. + * + * This constructor initializes a TempProbesClass object with the specified pin assignments for channel selection and RTD connection. + * + * @param ch_sel0_pin The pin number for the first channel selection bit. + * @param ch_sel1_pin The pin number for the second channel selection bit. + * @param ch_sel2_pin The pin number for the third channel selection bit. + * @param rtd_th_pin The pin number for the RTD connection. + */ + TempProbesClass(PinName ch_sel0_pin = PD_6, PinName ch_sel1_pin = PI_4, PinName ch_sel2_pin = PG_10, PinName rtd_th_pin = PC_15); + ~TempProbesClass(); + + /** + * @brief Initialize the TempProbesClass with the specified temperature probe type and I/O address. + * + * @param tempprobe_type The type of temperature probe (RTD or thermocouple). + * @param io_address The I/O address for communication with the digital converters (default is THREE_WIRE). + * @return true If initialization is successful, false otherwise. + */ + bool begin(uint8_t tempprobe_type, uint8_t io_address = THREE_WIRE); + + /** + * @brief Select the input channel to be read (3 channels available). + * + * @param channel The channel number (0-2) to be selected for temperature reading. + */ + void selectChannel(int channel); + + /** + * @brief Disable the temperature sensors and release any resources. + */ + void end(); + + // Instances of the MAX31865 and MAX31855 digital converter classes for RTD and thermocouple respectively + MAX31865Class RTD = MAX31865Class(PA_6); + MAX31855Class TC = MAX31855Class(7); - /** - * Select the input channel to be read (3 channels available) - * - * @param channel (0-2) - */ - void selectChannel(int channel); - - /** - * Enable the CS of the Thermocouple to digital converter - * Disable the CS for the RTD to digital converter - */ - void enableTC(); - - /** - * Enable the CS of the RDT to digital converter. - * Disable the CS of the Thermocouple to digital converter - */ - void enableRTD(); - - /** - * Disable Chip select for both RTD and thermocouple digital converters. - * - */ - void disableCS(); - - MAX31865Class rtd = MAX31865Class(PA_6); - MAX31855Class tc = MAX31855Class(7); private: - mbed::DigitalOut ch_sel[3] = { mbed::DigitalOut(PD_6), mbed::DigitalOut(PI_4), mbed::DigitalOut(PG_10)}; - mbed::DigitalOut rtd_th = mbed::DigitalOut(PC_15); + PinName _ch_sel0; // Pin for the first channel selection bit + PinName _ch_sel1; // Pin for the second channel selection bit + PinName _ch_sel2; // Pin for the third channel selection bit + PinName _rtd_th; // Pin for the RTD connection + + /** + * @brief Enable the chip select (CS) of the Thermocouple to digital converter and disable the CS for the RTD to digital converter. + */ + void _enableTC(); + + /** + * @brief Enable the chip select (CS) of the RTD to digital converter and disable the CS of the Thermocouple to digital converter. + */ + void _enableRTD(); + + /** + * @brief Disable chip select (CS) for both RTD and thermocouple digital converters. + */ + void _disableCS(); }; -extern TempProbesClass temp_probes; \ No newline at end of file +extern TempProbesClass MachineControl_TempProbes; + +#endif /* __TEMPPROBES_CLASS_H */ From c28bb65bdab9e9b215fbacb896181c3d78aaa41e Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 26 Jul 2023 11:10:56 +0200 Subject: [PATCH 15/47] RtcController Class refactoring --- examples/RTC/RTC.ino | 34 ++++++++++----------- examples/RTC_Alarm/RTC_Alarm.ino | 28 +++++++++--------- src/Arduino_MachineControl.h | 17 +---------- src/Objects.cpp | 1 - src/RtcControllerClass.cpp | 21 +++++++++++++ src/RtcControllerClass.h | 51 ++++++++++++++++++++++++++++++++ 6 files changed, 103 insertions(+), 49 deletions(-) create mode 100644 src/RtcControllerClass.cpp create mode 100644 src/RtcControllerClass.h diff --git a/examples/RTC/RTC.ino b/examples/RTC/RTC.ino index 954e237..496ba3c 100644 --- a/examples/RTC/RTC.ino +++ b/examples/RTC/RTC.ino @@ -12,8 +12,6 @@ */ #include -using namespace machinecontrol; - int years = 20; int months = 9; int days = 24; @@ -28,38 +26,38 @@ void setup() { } Serial.println("Initialization"); - if(!rtc_controller.begin()) { + if(!MachineControl_RTCController.begin()) { Serial.println("Initialization fail!"); } Serial.println("Initialization Done!"); // APIs to set date's fields: years, months, days, hours, minutes and seconds // The RTC time can be set as epoch, using one of the following two options: - // - Calendar time: rtc_controller.setEpoch(years, months, days, hours, minutes, seconds); - // - UTC time: rtc_controller.setEpoch(date_in_seconds); - rtc_controller.setYears(years); - rtc_controller.setMonths(months); - rtc_controller.setDays(days); - rtc_controller.setHours(hours); - rtc_controller.setMinutes(minutes); - rtc_controller.setSeconds(seconds); - rtc_controller.setEpoch(); + // - Calendar time: MachineControl_RTCController.setEpoch(years, months, days, hours, minutes, seconds); + // - UTC time: MachineControl_RTCController.setEpoch(date_in_seconds); + MachineControl_RTCController.setYears(years); + MachineControl_RTCController.setMonths(months); + MachineControl_RTCController.setDays(days); + MachineControl_RTCController.setHours(hours); + MachineControl_RTCController.setMinutes(minutes); + MachineControl_RTCController.setSeconds(seconds); + MachineControl_RTCController.setEpoch(); } void loop() { // APIs to get date's fields. Serial.print("Date: "); - Serial.print(rtc_controller.getYears()); + Serial.print(MachineControl_RTCController.getYears()); Serial.print("/"); - Serial.print(rtc_controller.getMonths()); + Serial.print(MachineControl_RTCController.getMonths()); Serial.print("/"); - Serial.print(rtc_controller.getDays()); + Serial.print(MachineControl_RTCController.getDays()); Serial.print(" - "); - Serial.print(rtc_controller.getHours()); + Serial.print(MachineControl_RTCController.getHours()); Serial.print(":"); - Serial.print(rtc_controller.getMinutes()); + Serial.print(MachineControl_RTCController.getMinutes()); Serial.print(":"); - Serial.println(rtc_controller.getSeconds()); + Serial.println(MachineControl_RTCController.getSeconds()); time_t utc_time = time(NULL); Serial.print("Date as UTC time: "); Serial.println(utc_time); diff --git a/examples/RTC_Alarm/RTC_Alarm.ino b/examples/RTC_Alarm/RTC_Alarm.ino index c455af6..c22a9a4 100644 --- a/examples/RTC_Alarm/RTC_Alarm.ino +++ b/examples/RTC_Alarm/RTC_Alarm.ino @@ -29,7 +29,7 @@ void setup() { } Serial.println("Initialization"); - if (!rtc_controller.begin()) { + if (!MachineControl_RTCController.begin()) { Serial.println("Initialization fail!"); } @@ -37,14 +37,14 @@ void setup() { Serial.println("Initialization Done!"); // APIs to set date's fields: hours, minutes and seconds - rtc_controller.setHours(hours); - rtc_controller.setMinutes(minutes); - rtc_controller.setSeconds(seconds); + MachineControl_RTCController.setHours(hours); + MachineControl_RTCController.setMinutes(minutes); + MachineControl_RTCController.setSeconds(seconds); // Enables Alarm on PCF8563T - rtc_controller.enableAlarm(); + MachineControl_RTCController.enableAlarm(); // set the minutes at which the alarm should rise - rtc_controller.setMinuteAlarm(46); + MachineControl_RTCController.setMinuteAlarm(46); // Attach an interrupt to the RTC interrupt pin attachInterrupt(RTC_INT, callback_alarm, FALLING); @@ -56,23 +56,23 @@ void loop() { if (alarm_flag) { Serial.println("Alarm!!"); detachInterrupt(RTC_INT); - rtc_controller.setSeconds(seconds); - rtc_controller.setMinuteAlarm(minutes + counter); - rtc_controller.clearAlarm(); + MachineControl_RTCController.setSeconds(seconds); + MachineControl_RTCController.setMinuteAlarm(minutes + counter); + MachineControl_RTCController.clearAlarm(); attachInterrupt(RTC_INT, callback_alarm, FALLING); alarm_flag = false; // To disable the alarm uncomment the following line: - // rtc_controller.disableAlarm(); + // MachineControl_RTCController.disableAlarm(); } // APIs to get date's fields. - //Serial.println(digitalRead(rtc_controller.int_pin)); - Serial.print(rtc_controller.getHours()); + //Serial.println(digitalRead(MachineControl_RTCController.int_pin)); + Serial.print(MachineControl_RTCController.getHours()); Serial.print(":"); - Serial.print(rtc_controller.getMinutes()); + Serial.print(MachineControl_RTCController.getMinutes()); Serial.print(":"); - Serial.println(rtc_controller.getSeconds()); + Serial.println(MachineControl_RTCController.getSeconds()); delay(1000); } diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index bc8dbf4..50d7888 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -7,7 +7,6 @@ #include "utility/QEI/QEI.h" #include "utility/ioexpander/ArduinoIOExpander.h" #include "utility/RTC/PCF8563T.h" -#include "utility/RTC/PCF8563T.h" #include #include @@ -19,6 +18,7 @@ #include "ProgrammableDIOClass.h" #include "ProgrammableDINClass.h" #include "TempProbesClass.h" +#include "RtcControllerClass.h" namespace machinecontrol { @@ -128,21 +128,6 @@ class EncoderClass { extern EncoderClass encoders; -/** - * The RtcControllerClass is a wrapper for the PCF8563TClass() that is used to - * set and get the time to/from the PCF8563T RTC. - * - */ -class RtcControllerClass : public PCF8563TClass { -public: - mbed::DigitalIn int_pin = mbed::DigitalIn(PB_9,PullUp); -private: - -}; - -extern RtcControllerClass rtc_controller; - - /** * The USB Class is used to enable/disable the power of the USBA (Host) and configure * the callbacks for the different host types (i.e. Keyboard, mouse, storage device etc). diff --git a/src/Objects.cpp b/src/Objects.cpp index 69054e4..7732c6c 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -3,6 +3,5 @@ namespace machinecontrol { COMMClass comm_protocols; EncoderClass encoders; -RtcControllerClass rtc_controller; USBClass usb_controller; } diff --git a/src/RtcControllerClass.cpp b/src/RtcControllerClass.cpp new file mode 100644 index 0000000..e009273 --- /dev/null +++ b/src/RtcControllerClass.cpp @@ -0,0 +1,21 @@ +/** + * @file RtcControllerClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the RtcControllerClass, a wrapper for the PCF8563T RTC of the Portenta Machine Control. + */ + +/* Includes -----------------------------------------------------------------*/ +#include "RtcControllerClass.h" + +/* Functions -----------------------------------------------------------------*/ +RtcControllerClass::RtcControllerClass(PinName int_pin) + : _int{int_pin} +{ + pinMode(_int, INPUT_PULLUP); +} + +RtcControllerClass::~RtcControllerClass() +{ } + +RtcControllerClass MachineControl_RTCController; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/RtcControllerClass.h b/src/RtcControllerClass.h new file mode 100644 index 0000000..089e737 --- /dev/null +++ b/src/RtcControllerClass.h @@ -0,0 +1,51 @@ +/** + * @file RtcControllerClass.h + * @author Leonardo Cavagnis + * @brief Header file for the RtcControllerClass, a wrapper for the PCF8563T RTC of the Portenta Machine Control. + * + * This header file defines the RtcControllerClass, which serves as a wrapper for the PCF8563TClass. + * The class allows setting and getting the time to/from the PCF8563T RTC (Real-Time Clock). + */ + +#ifndef __RTC_CONTROLLER_CLASS_H +#define __RTC_CONTROLLER_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include "utility/RTC/PCF8563T.h" +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class RtcControllerClass + * @brief Class for controlling the PCF8563T RTC. + * + * This class serves as a wrapper for the PCF8563TClass and provides additional functionalities + * for controlling the Real-Time Clock on the target platform. + */ +class RtcControllerClass : public PCF8563TClass { + public: + /** + * @brief Construct a RtcControllerClass object with an interrupt pin. + * + * This constructor initializes a RtcControllerClass object. + * + * @param int_pin The pin number for the interrupt pin (default is PB_9). + */ + RtcControllerClass(PinName int_pin = PB_9); + + /** + * @brief Destructor for the RtcControllerClass. + * + * This destructor is responsible for cleaning up any resources associated with the RtcControllerClass. + */ + ~RtcControllerClass(); + + private: + PinName _int; // Pin for the interrupt +}; + +extern RtcControllerClass MachineControl_RTCController; + +#endif /* __RTC_CONTROLLER_CLASS_H */ From 4edfa6069f5d0340b237d1e2d69c9750dc0eb5b7 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 26 Jul 2023 11:20:34 +0200 Subject: [PATCH 16/47] create USBClass as separate module --- src/Arduino_MachineControl.h | 44 +----------------------------------- src/USBClass.cpp | 19 ++++++++++++++++ src/USBClass.h | 34 ++++++++++++++++++++++++++++ 3 files changed, 54 insertions(+), 43 deletions(-) create mode 100644 src/USBClass.cpp create mode 100644 src/USBClass.h diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index 50d7888..fc9b178 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -19,6 +19,7 @@ #include "ProgrammableDINClass.h" #include "TempProbesClass.h" #include "RtcControllerClass.h" +#include "USBClass.h" namespace machinecontrol { @@ -128,48 +129,5 @@ class EncoderClass { extern EncoderClass encoders; -/** - * The USB Class is used to enable/disable the power of the USBA (Host) and configure - * the callbacks for the different host types (i.e. Keyboard, mouse, storage device etc). - */ -class USBClass { -public: - USBClass() - : _power{PB_14, 0} - , _usbflag{PB_15} - {}; - - /** - * Enable power to USBA VBUS. - */ - void powerEnable() { - _power = 0; - } - - /** - * Disable power to USBA VBUS. - */ - void powerDisable() { - _power = 1; - } - - /** - * Flag to indicate overcurrent, overtemperature, or reverse−voltage conditions on the USBA VBUS. - * Active−low open−drain output. - * @return true if OK, false if fault - */ - bool vflagRead() { - return _usbflag; - } - -private: - mbed::DigitalOut _power; - mbed::DigitalIn _usbflag; -}; - - -extern USBClass usb_controller; - - } #endif diff --git a/src/USBClass.cpp b/src/USBClass.cpp new file mode 100644 index 0000000..c0d61d9 --- /dev/null +++ b/src/USBClass.cpp @@ -0,0 +1,19 @@ +#include "USBClass.h" + +USBClass::USBClass() + : _power{PB_14, 0}, _usbflag{PB_15} +{ } + +void USBClass::powerEnable() { + _power = 0; +} + +void USBClass::powerDisable() { + _power = 1; +} + +bool USBClass::vflagRead() { + return _usbflag; +} + +USBClass usb_controller; \ No newline at end of file diff --git a/src/USBClass.h b/src/USBClass.h new file mode 100644 index 0000000..c44edeb --- /dev/null +++ b/src/USBClass.h @@ -0,0 +1,34 @@ +#include +#include + +/** + * The USB Class is used to enable/disable the power of the USBA (Host) and configure + * the callbacks for the different host types (i.e. Keyboard, mouse, storage device etc). + */ +class USBClass { +public: + USBClass(); + + /** + * Enable power to USBA VBUS. + */ + void powerEnable(); + + /** + * Disable power to USBA VBUS. + */ + void powerDisable(); + + /** + * Flag to indicate overcurrent, overtemperature, or reverse−voltage conditions on the USBA VBUS. + * Active−low open−drain output. + * @return true if OK, false if fault + */ + bool vflagRead(); + +private: + mbed::DigitalOut _power; + mbed::DigitalIn _usbflag; +}; + +extern USBClass usb_controller; \ No newline at end of file From e10ffbc325c1b15a17577b60712986c1f43c7024 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 26 Jul 2023 15:27:37 +0200 Subject: [PATCH 17/47] USBClass refactoring --- examples/USB_host/USB_host.ino | 6 +- src/USBClass.cpp | 52 ++++++++++++++--- src/USBClass.h | 103 +++++++++++++++++++++++++-------- 3 files changed, 125 insertions(+), 36 deletions(-) diff --git a/examples/USB_host/USB_host.ino b/examples/USB_host/USB_host.ino index 69cc975..af92861 100644 --- a/examples/USB_host/USB_host.ino +++ b/examples/USB_host/USB_host.ino @@ -3,8 +3,6 @@ #include "TUSB_helpers.h" -using namespace machinecontrol; - // Redirect log output from MbedOS and low-level libraries to Serial REDIRECT_STDOUT_TO(Serial); @@ -13,9 +11,9 @@ USBHost usb; void setup() { Serial1.begin(115200); - usb_controller.powerEnable(); + MachineControl_USBController.begin(); + usb.Init(USB_CORE_ID_FS, class_table); - } void loop() { diff --git a/src/USBClass.cpp b/src/USBClass.cpp index c0d61d9..6b818c9 100644 --- a/src/USBClass.cpp +++ b/src/USBClass.cpp @@ -1,19 +1,53 @@ +/** + * @file USBClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the USB Controller of the Portenta Machine Control. + */ + +/* Includes -----------------------------------------------------------------*/ #include "USBClass.h" -USBClass::USBClass() - : _power{PB_14, 0}, _usbflag{PB_15} +/* Functions -----------------------------------------------------------------*/ +USBClass::USBClass(PinName power_pin, PinName usbflag_pin) + : _power{power_pin}, _usbflag{usbflag_pin} +{ } + +USBClass::~USBClass() { } -void USBClass::powerEnable() { - _power = 0; +bool USBClass::begin() { + pinMode(_power, OUTPUT); + pinMode(_usbflag, INPUT); + + _powerEnable(); + + return true; +} + +void USBClass::end() { + _powerDisable(); +} + +bool USBClass::getFaultStatus() { + bool res = false; + + if (digitalRead(_usbflag) == LOW) { + /* Active−low, asserted during overcurrent, overtemperature, or reverse−voltage conditions. */ + res = true; + } else { + res = false; + } + + return res; } -void USBClass::powerDisable() { - _power = 1; +void USBClass::_powerEnable() { + digitalWrite(_power, LOW); } -bool USBClass::vflagRead() { - return _usbflag; +void USBClass::_powerDisable() { + digitalWrite(_power, HIGH); } -USBClass usb_controller; \ No newline at end of file +USBClass MachineControl_USBController; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/USBClass.h b/src/USBClass.h index c44edeb..f1f4e44 100644 --- a/src/USBClass.h +++ b/src/USBClass.h @@ -1,34 +1,91 @@ +/** + * @file USBControllerClass.h + * @author Leonardo Cavagnis + * @brief Header file for the USB Controller of the Portenta Machine Control. + * + * This library provides a class to manage the USB functionality of the Portenta Machine Control. + * It enables or disables the power of the USB Host (USBA) and provides methods to check the fault status. + */ + +#ifndef __USB_CONTROLLER_CLASS_H +#define __USB_CONTROLLER_CLASS_H + +/* Includes -------------------------------------------------------------------*/ #include #include +/* Class ----------------------------------------------------------------------*/ + /** - * The USB Class is used to enable/disable the power of the USBA (Host) and configure - * the callbacks for the different host types (i.e. Keyboard, mouse, storage device etc). + * @class USBClass + * @brief Class for managing the USB functionality of the Portenta Machine Control. + * + * This class allows enabling or disabling the power of the USB Host (USBA) and checking for any fault status. */ class USBClass { public: - USBClass(); - - /** - * Enable power to USBA VBUS. - */ - void powerEnable(); - - /** - * Disable power to USBA VBUS. - */ - void powerDisable(); - - /** - * Flag to indicate overcurrent, overtemperature, or reverse−voltage conditions on the USBA VBUS. - * Active−low open−drain output. - * @return true if OK, false if fault - */ - bool vflagRead(); + /** + * @brief Construct a USBClass object. + * + * This constructor initializes a USBClass object with the specified pin assignments for power control and fault status. + * + * @param power_pin The pin number for controlling the power to the USBA VBUS. + * @param usbflag_pin The pin number for reading the fault status of the USBA VBUS. + */ + USBClass(PinName power_pin = PB_14, PinName usbflag_pin = PB_15); + + /** + * @brief Destruct the USBClass object. + * + * This destructor releases any resources used by the USBClass object. + */ + ~USBClass(); + + /** + * @brief Begin the USB functionality. + * + * This method initializes the USB functionality by enabling power to the USBA VBUS. + * + * @return true If the initialization is successful, false otherwise. + */ + bool begin(); + + /** + * @brief End the USB functionality. + * + * This method disables power to the USBA VBUS and releases any resources used by the USBClass object. + */ + void end(); + + /** + * @brief Get the fault status of the USBA VBUS. + * + * This method reads the fault status of the USBA VBUS to check for overcurrent, overtemperature, + * or reverse-voltage conditions. + * + * @return true if there is a fault, false if everything is okay. + */ + bool getFaultStatus(); private: - mbed::DigitalOut _power; - mbed::DigitalIn _usbflag; + PinName _power; // Pin for controlling the power to the USBA VBUS + PinName _usbflag; // Pin for reading the fault status of the USBA VBUS + + /** + * @brief Enable power to the USBA VBUS. + * + * This private method is used to enable power to the USBA VBUS. + */ + void _powerEnable(); + + /** + * @brief Disable power to the USBA VBUS. + * + * This private method is used to disable power to the USBA VBUS. + */ + void _powerDisable(); }; -extern USBClass usb_controller; \ No newline at end of file +extern USBClass MachineControl_USBController; + +#endif /* __USB_CONTROLLER_CLASS_H */ \ No newline at end of file From 02506aac827618148dffe9b56310caea1cc620ac Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 26 Jul 2023 16:15:05 +0200 Subject: [PATCH 18/47] Encoder class refactoring --- examples/Encoders/Encoders.ino | 14 +++---- src/Arduino_MachineControl.h | 35 +---------------- src/EncoderClass.cpp | 33 +++++++++++++++++ src/EncoderClass.h | 68 ++++++++++++++++++++++++++++++++++ src/Objects.cpp | 1 - 5 files changed, 108 insertions(+), 43 deletions(-) create mode 100644 src/EncoderClass.cpp create mode 100644 src/EncoderClass.h diff --git a/examples/Encoders/Encoders.ino b/examples/Encoders/Encoders.ino index 0e91d45..8fb5960 100644 --- a/examples/Encoders/Encoders.ino +++ b/examples/Encoders/Encoders.ino @@ -1,7 +1,5 @@ #include -using namespace machinecontrol; - void setup() { Serial.begin(9600); while (!Serial); @@ -10,19 +8,19 @@ void setup() { void loop() { // put your main code here, to run repeatedly: Serial.print("Encoder 0 State: "); - Serial.println(encoders[0].getCurrentState(),BIN); + Serial.println(MachineControl_Encoders[0].getCurrentState(),BIN); Serial.print("Encoder 0 Pulses: "); - Serial.println(encoders[0].getPulses()); + Serial.println(MachineControl_Encoders[0].getPulses()); Serial.print("Encoder 0 Revolutions: "); - Serial.println(encoders[0].getRevolutions()); + Serial.println(MachineControl_Encoders[0].getRevolutions()); Serial.println(); Serial.print("Encoder 1 State: "); - Serial.println(encoders[1].getCurrentState(),BIN); + Serial.println(MachineControl_Encoders[1].getCurrentState(),BIN); Serial.print("Encoder 1 Pulses: "); - Serial.println(encoders[1].getPulses()); + Serial.println(MachineControl_Encoders[1].getPulses()); Serial.print("Encoder 1 Revolutions: "); - Serial.println(encoders[1].getRevolutions()); + Serial.println(MachineControl_Encoders[1].getRevolutions()); Serial.println(); delay(25); } diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index fc9b178..b1fca19 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -20,6 +20,7 @@ #include "TempProbesClass.h" #include "RtcControllerClass.h" #include "USBClass.h" +#include "EncoderClass.h" namespace machinecontrol { @@ -95,39 +96,5 @@ class COMMClass { extern COMMClass comm_protocols; -/* - TODO: writeme - Use QEI library for mbed since it implements index pin -*/ - /** - * The EncoderClass is a wrapper for manipulating Quadrature Encoder Interface devices. - */ -class EncoderClass { -public: - /** - * returns the encoder variable depending on the index - * @param index integer for selecting the encoder (0 or 1) - * @return enc_0 for index = 0, enc_1 for index = 1 - */ - EncoderClass() - : enc_0{PJ_8, PH_12, PH_11, 0} - , enc_1{PC_13, PI_7, PJ_10, 0} {}; - - - QEI& operator[](int index) { - switch (index) { - case 0: - return enc_0; - case 1: - return enc_1; - } - } -private: - QEI enc_0; - QEI enc_1; -}; - -extern EncoderClass encoders; - } #endif diff --git a/src/EncoderClass.cpp b/src/EncoderClass.cpp new file mode 100644 index 0000000..1026503 --- /dev/null +++ b/src/EncoderClass.cpp @@ -0,0 +1,33 @@ +/** + * @file EncoderClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the EncoderClass of the Portenta Machine Control. + */ + +/* Includes -----------------------------------------------------------------*/ +#include "EncoderClass.h" + +/* Functions -----------------------------------------------------------------*/ +EncoderClass::EncoderClass(PinName enc0_A_pin, PinName enc0_B_pin, PinName enc0_I_pin, + PinName enc1_A_pin, PinName enc1_B_pin, PinName enc1_I_pin) + : enc_0(enc0_A_pin, enc0_B_pin, enc0_I_pin, 0), + enc_1(enc1_A_pin, enc1_B_pin, enc1_I_pin, 0) +{ } + +EncoderClass::~EncoderClass() +{ } + +QEI& EncoderClass::operator[](int index) { + switch (index) { + case 0: + return enc_0; + case 1: + return enc_1; + default: + // Return encoder 0 by default if an invalid index is provided + return enc_0; + } +} + +EncoderClass MachineControl_Encoders; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/EncoderClass.h b/src/EncoderClass.h new file mode 100644 index 0000000..faf13c6 --- /dev/null +++ b/src/EncoderClass.h @@ -0,0 +1,68 @@ +/** + * @file EncoderClass.h + * @author Leonardo Cavagnis + * @brief Header file for the EncoderClass of the Portenta Machine Control. + * + * This library provides a class to manage the Quadrature Encoder Interface devices + * of the Portenta Machine Control. It allows interfacing with two encoders through + * the QEI (Quadrature Encoder Interface) library and provides methods to access + * and control each encoder individually. + */ + +#ifndef __ENCODER_CLASS_H +#define __ENCODER_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include "utility/QEI/QEI.h" +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class EncoderClass + * @brief Class for managing Quadrature Encoder Interface devices of the Portenta Machine Control. + */ +class EncoderClass { +public: + /** + * @brief Construct an EncoderClass object. + * + * This constructor initializes the two QEI objects for encoder 0 and encoder 1 + * with the specified pin assignments. + * + * @param enc0_A_pin Pin assignment for encoder 0 channel A (default: PA_0). + * @param enc0_B_pin Pin assignment for encoder 0 channel B (default: PB_0). + * @param enc0_I_pin Pin assignment for encoder 0 Index channel (default: PC_0). + * @param enc1_A_pin Pin assignment for encoder 1 channel A (default: PD_0). + * @param enc1_B_pin Pin assignment for encoder 1 channel B (default: PE_0). + * @param enc1_I_pin Pin assignment for encoder 1 Index channel (default: PF_0). + */ + EncoderClass(PinName enc0_A_pin = PJ_8, PinName enc0_B_pin = PH_12, PinName enc0_I_pin = PH_11, + PinName enc1_A_pin = PC_13, PinName enc1_B_pin = PI_7, PinName enc1_I_pin = PJ_10); + + /** + * @brief Destruct the EncoderClass object. + * + * This destructor releases any resources used by the EncoderClass object. + */ + ~EncoderClass(); + + /** + * @brief Get the QEI object for the specified encoder index. + * + * This method returns a reference to the QEI object for the specified encoder index. + * + * @param index The index for selecting the encoder (0 or 1). + * @return A reference to the corresponding QEI object. + */ + QEI& operator[](int index); + +private: + QEI enc_0; // QEI object for encoder 0 + QEI enc_1; // QEI object for encoder 1 +}; + +extern EncoderClass MachineControl_Encoders; + +#endif /* __ENCODER_CLASS_H */ \ No newline at end of file diff --git a/src/Objects.cpp b/src/Objects.cpp index 7732c6c..2a6c5a7 100644 --- a/src/Objects.cpp +++ b/src/Objects.cpp @@ -2,6 +2,5 @@ namespace machinecontrol { COMMClass comm_protocols; -EncoderClass encoders; USBClass usb_controller; } From b0458addb91b68de83c0a01ab927499807df391e Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 26 Jul 2023 16:52:31 +0200 Subject: [PATCH 19/47] create COMMClass as separate module --- examples/CAN/ReadCan/ReadCan.ino | 2 - examples/CAN/WriteCan/WriteCan.ino | 1 - examples/RS232/RS232.ino | 2 - .../RS485_fullduplex/RS485_fullduplex.ino | 2 - .../RS485_halfduplex/RS485_halfduplex.ino | 2 - src/Arduino_MachineControl.h | 93 +------------------ src/COMMClass.cpp | 47 ++++++++++ src/COMMClass.h | 49 ++++++++++ src/EncoderClass.cpp | 10 +- src/EncoderClass.h | 4 +- src/Objects.cpp | 6 -- 11 files changed, 107 insertions(+), 111 deletions(-) create mode 100644 src/COMMClass.cpp create mode 100644 src/COMMClass.h delete mode 100644 src/Objects.cpp diff --git a/examples/CAN/ReadCan/ReadCan.ino b/examples/CAN/ReadCan/ReadCan.ino index c7273f7..7dc6fb2 100644 --- a/examples/CAN/ReadCan/ReadCan.ino +++ b/examples/CAN/ReadCan/ReadCan.ino @@ -12,8 +12,6 @@ #include #include -using namespace machinecontrol; - #define DATARATE_2MB 2000000 #define DATARATE_1_5MB 1500000 #define DATARATE_1MB 1000000 diff --git a/examples/CAN/WriteCan/WriteCan.ino b/examples/CAN/WriteCan/WriteCan.ino index 6250cfd..6a435af 100644 --- a/examples/CAN/WriteCan/WriteCan.ino +++ b/examples/CAN/WriteCan/WriteCan.ino @@ -11,7 +11,6 @@ */ #include #include -using namespace machinecontrol; #define DATARATE_2MB 2000000 #define DATARATE_1_5MB 1500000 diff --git a/examples/RS232/RS232.ino b/examples/RS232/RS232.ino index 97b4a0b..ab50520 100644 --- a/examples/RS232/RS232.ino +++ b/examples/RS232/RS232.ino @@ -17,8 +17,6 @@ #include -using namespace machinecontrol; - constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; diff --git a/examples/RS485_fullduplex/RS485_fullduplex.ino b/examples/RS485_fullduplex/RS485_fullduplex.ino index 4c1a04a..2476e06 100644 --- a/examples/RS485_fullduplex/RS485_fullduplex.ino +++ b/examples/RS485_fullduplex/RS485_fullduplex.ino @@ -17,8 +17,6 @@ #include "Arduino_MachineControl.h" -using namespace machinecontrol; - constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; unsigned long counter = 0; diff --git a/examples/RS485_halfduplex/RS485_halfduplex.ino b/examples/RS485_halfduplex/RS485_halfduplex.ino index 3e5de9d..882313d 100644 --- a/examples/RS485_halfduplex/RS485_halfduplex.ino +++ b/examples/RS485_halfduplex/RS485_halfduplex.ino @@ -16,8 +16,6 @@ #include "Arduino_MachineControl.h" -using namespace machinecontrol; - constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index b1fca19..4ed792e 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -1,16 +1,5 @@ -#ifndef __MACHINE_CONTROL_H__ -#define __MACHINE_CONTROL_H__ - -#include "utility/MAX31865/MAX31865.h" -#include "utility/THERMOCOUPLE/MAX31855.h" -#include -#include "utility/QEI/QEI.h" -#include "utility/ioexpander/ArduinoIOExpander.h" -#include "utility/RTC/PCF8563T.h" - -#include -#include -#include +#ifndef __ARDUINO_MACHINE_CONTROL_H +#define __ARDUINO_MACHINE_CONTROL_H #include "AnalogInClass.h" #include "AnalogOutClass.h" @@ -21,80 +10,6 @@ #include "RtcControllerClass.h" #include "USBClass.h" #include "EncoderClass.h" +#include "COMMClass.h" -namespace machinecontrol { - -/** - * The COMMClass is used to initialize the CAN and RS485 LEDs and - * establish the power mode of the CAN bus. - */ -class COMMClass { -public: - // to be tested: check if can be made a big pin initialization - - /** - * Shutdown RS485 and CAN LEDs - */ - void init() { - //SHUTDOWN OF RS485 LEDS - digitalWrite(PinNameToIndex(PA_0), LOW); - digitalWrite(PinNameToIndex(PI_9), LOW); - //SHUTDOWN OF CAN LEDS - digitalWrite(PinNameToIndex(PB_8), HIGH); - digitalWrite(PinNameToIndex(PH_13), HIGH); - - // SET DEFAULTS for RS485 - rs485Enable(false); - rs485ModeRS232(false); - rs485FullDuplex(false); - rs485YZTerm(false); - rs485ABTerm(false); - rs485Slew(false); - } - - /** - * Set the CAN transceiver in Normal mode. In this mode, the transceiver - * can transmit and receive data via the bus lines CANH and CANL. - */ - void enableCAN() { - can_disable = 0; - } - - /** - * Set the CAN transceiver in standby (low power) mode. In this mode the - * transceiver will not be able to transmit or correctly receive data via the bus lines. - * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, - * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) - * bus are reflected on pin RXD. - */ - void disableCAN() { - can_disable = 1; - } - - arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; - mbed::CAN can {PB_8, PH_13}; - - RS485Class rs485 {_UART4_, PinNameToIndex(PA_0), PinNameToIndex(PI_13), PinNameToIndex(PI_10)}; - - void rs485Enable(bool enable) { digitalWrite(PinNameToIndex(PG_9), enable ? HIGH : LOW); } - void rs485ModeRS232(bool enable) { digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); } - void rs485YZTerm(bool enable) { digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); } - void rs485ABTerm(bool enable) { digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); } - void rs485Slew(bool enable) { digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); } - void rs485FullDuplex(bool enable) { - digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); - if (enable) { - // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled - rs485YZTerm(true); - rs485ABTerm(true); - } - } - -private: - mbed::DigitalOut can_disable = mbed::DigitalOut(PA_13, 0); -}; - -extern COMMClass comm_protocols; - -} -#endif +#endif /* __ARDUINO_MACHINE_CONTROL_H */ diff --git a/src/COMMClass.cpp b/src/COMMClass.cpp new file mode 100644 index 0000000..96670a6 --- /dev/null +++ b/src/COMMClass.cpp @@ -0,0 +1,47 @@ +#include "COMMClass.h" + +void COMMClass::init() { + //SHUTDOWN OF RS485 LEDS + digitalWrite(PinNameToIndex(PA_0), LOW); + digitalWrite(PinNameToIndex(PI_9), LOW); + //SHUTDOWN OF CAN LEDS + digitalWrite(PinNameToIndex(PB_8), HIGH); + digitalWrite(PinNameToIndex(PH_13), HIGH); + + // SET DEFAULTS for RS485 + rs485Enable(false); + rs485ModeRS232(false); + rs485FullDuplex(false); + rs485YZTerm(false); + rs485ABTerm(false); + rs485Slew(false); +} + +void COMMClass::enableCAN() { + can_disable = 0; +} + +void COMMClass::disableCAN() { + can_disable = 1; +} + +void COMMClass::rs485Enable(bool enable) { digitalWrite(PinNameToIndex(PG_9), enable ? HIGH : LOW); } + +void COMMClass::rs485ModeRS232(bool enable) { digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); } + +void COMMClass::rs485YZTerm(bool enable) { digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); } + +void COMMClass::rs485ABTerm(bool enable) { digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); } + +void COMMClass::rs485Slew(bool enable) { digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); } + +void COMMClass::rs485FullDuplex(bool enable) { + digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); + if (enable) { + // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled + rs485YZTerm(true); + rs485ABTerm(true); + } +} + +COMMClass comm_protocols; \ No newline at end of file diff --git a/src/COMMClass.h b/src/COMMClass.h new file mode 100644 index 0000000..2c292a9 --- /dev/null +++ b/src/COMMClass.h @@ -0,0 +1,49 @@ +#include +#include +#include +#include + +/** + * The COMMClass is used to initialize the CAN and RS485 LEDs and + * establish the power mode of the CAN bus. + */ +class COMMClass { +public: + // to be tested: check if can be made a big pin initialization + + /** + * Shutdown RS485 and CAN LEDs + */ + void init(); + + /** + * Set the CAN transceiver in Normal mode. In this mode, the transceiver + * can transmit and receive data via the bus lines CANH and CANL. + */ + void enableCAN(); + + /** + * Set the CAN transceiver in standby (low power) mode. In this mode the + * transceiver will not be able to transmit or correctly receive data via the bus lines. + * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, + * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) + * bus are reflected on pin RXD. + */ + void disableCAN(); + + void rs485Enable(bool enable); + void rs485ModeRS232(bool enable); + void rs485YZTerm(bool enable); + void rs485ABTerm(bool enable); + void rs485Slew(bool enable); + void rs485FullDuplex(bool enable); + + arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; + mbed::CAN can {PB_8, PH_13}; + RS485Class rs485 {_UART4_, PinNameToIndex(PA_0), PinNameToIndex(PI_13), PinNameToIndex(PI_10)}; + +private: + mbed::DigitalOut can_disable = mbed::DigitalOut(PA_13, 0); +}; + +extern COMMClass comm_protocols; \ No newline at end of file diff --git a/src/EncoderClass.cpp b/src/EncoderClass.cpp index 1026503..50bdaf8 100644 --- a/src/EncoderClass.cpp +++ b/src/EncoderClass.cpp @@ -10,8 +10,8 @@ /* Functions -----------------------------------------------------------------*/ EncoderClass::EncoderClass(PinName enc0_A_pin, PinName enc0_B_pin, PinName enc0_I_pin, PinName enc1_A_pin, PinName enc1_B_pin, PinName enc1_I_pin) - : enc_0(enc0_A_pin, enc0_B_pin, enc0_I_pin, 0), - enc_1(enc1_A_pin, enc1_B_pin, enc1_I_pin, 0) + : _enc0(enc0_A_pin, enc0_B_pin, enc0_I_pin, 0), + _enc1(enc1_A_pin, enc1_B_pin, enc1_I_pin, 0) { } EncoderClass::~EncoderClass() @@ -20,12 +20,12 @@ EncoderClass::~EncoderClass() QEI& EncoderClass::operator[](int index) { switch (index) { case 0: - return enc_0; + return _enc0; case 1: - return enc_1; + return _enc1; default: // Return encoder 0 by default if an invalid index is provided - return enc_0; + return _enc0; } } diff --git a/src/EncoderClass.h b/src/EncoderClass.h index faf13c6..a8e174f 100644 --- a/src/EncoderClass.h +++ b/src/EncoderClass.h @@ -59,8 +59,8 @@ class EncoderClass { QEI& operator[](int index); private: - QEI enc_0; // QEI object for encoder 0 - QEI enc_1; // QEI object for encoder 1 + QEI _enc0; // QEI object for encoder 0 + QEI _enc1; // QEI object for encoder 1 }; extern EncoderClass MachineControl_Encoders; diff --git a/src/Objects.cpp b/src/Objects.cpp deleted file mode 100644 index 2a6c5a7..0000000 --- a/src/Objects.cpp +++ /dev/null @@ -1,6 +0,0 @@ -#include "Arduino_MachineControl.h" - -namespace machinecontrol { -COMMClass comm_protocols; -USBClass usb_controller; -} From a6af34e35d18f2090c2759586fe3427441cac691 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 27 Jul 2023 17:00:02 +0200 Subject: [PATCH 20/47] COMM class refactoring --- examples/CAN/ReadCan/ReadCan.ino | 10 +- examples/CAN/WriteCan/WriteCan.ino | 13 +- examples/RS232/RS232.ino | 24 +-- .../RS485_fullduplex/RS485_fullduplex.ino | 26 +-- .../RS485_halfduplex/RS485_halfduplex.ino | 24 +-- src/COMMClass.cpp | 96 ++++++++--- src/COMMClass.h | 150 +++++++++++++----- 7 files changed, 232 insertions(+), 111 deletions(-) diff --git a/examples/CAN/ReadCan/ReadCan.ino b/examples/CAN/ReadCan/ReadCan.ino index 7dc6fb2..7aa847d 100644 --- a/examples/CAN/ReadCan/ReadCan.ino +++ b/examples/CAN/ReadCan/ReadCan.ino @@ -17,7 +17,6 @@ #define DATARATE_1MB 1000000 #define DATARATE_800KB 800000 - void setup() { Serial.begin(9600); while (!Serial) { @@ -25,15 +24,16 @@ void setup() { } Serial.println("Start CAN initialization"); - comm_protocols.enableCAN(); - comm_protocols.can.frequency(DATARATE_800KB); + MachineControl_CommProtocols.begin(); + MachineControl_CommProtocols.CANEnable(); + + MachineControl_CommProtocols.CAN.frequency(DATARATE_800KB); Serial.println("Initialization done"); } - void loop() { mbed::CANMessage msg; - if (comm_protocols.can.read(msg)) { + if (MachineControl_CommProtocols.CAN.read(msg)) { // Print the sender ID Serial.print("ID: "); diff --git a/examples/CAN/WriteCan/WriteCan.ino b/examples/CAN/WriteCan/WriteCan.ino index 6a435af..e32b9b0 100644 --- a/examples/CAN/WriteCan/WriteCan.ino +++ b/examples/CAN/WriteCan/WriteCan.ino @@ -17,7 +17,6 @@ #define DATARATE_1MB 1000000 #define DATARATE_800KB 800000 - void setup() { Serial.begin(9600); while (!Serial) { @@ -25,8 +24,10 @@ void setup() { } Serial.println("Start CAN initialization"); - comm_protocols.enableCAN(); - comm_protocols.can.frequency(DATARATE_800KB); + + MachineControl_CommProtocols.begin(); + MachineControl_CommProtocols.CANEnable(); + MachineControl_CommProtocols.CAN.frequency(DATARATE_800KB); Serial.println("Initialization done"); } @@ -37,12 +38,12 @@ int payload_size = 1; void loop() { mbed::CANMessage msg = mbed::CANMessage(13ul, &payload, payload_size); - if (comm_protocols.can.write(msg)) { + if (MachineControl_CommProtocols.CAN.write(msg)) { Serial.println("Message sent"); } else { Serial.println("Transmission Error: "); - Serial.println(comm_protocols.can.tderror()); - comm_protocols.can.reset(); + Serial.println(MachineControl_CommProtocols.CAN.tderror()); + MachineControl_CommProtocols.CAN.reset(); } delay(100); diff --git a/examples/RS232/RS232.ino b/examples/RS232/RS232.ino index ab50520..5875e58 100644 --- a/examples/RS232/RS232.ino +++ b/examples/RS232/RS232.ino @@ -34,7 +34,7 @@ void setup() Serial.println("Start RS232 initialization"); // Set the PMC Communication Protocols to default config - comm_protocols.init(); + MachineControl_CommProtocols.begin(); // RS485/RS232 default config is: // - RS485/RS232 system disabled @@ -43,22 +43,22 @@ void setup() // - No A/B and Y/Z 120 Ohm termination enabled // Enable the RS485/RS232 system - comm_protocols.rs485Enable(true); + MachineControl_CommProtocols.RS485Enable(); // Enable the RS232 mode - comm_protocols.rs485ModeRS232(true); + MachineControl_CommProtocols.RS485SetModeRS232(true); // Specify baudrate for RS232 communication - comm_protocols.rs485.begin(115200); + MachineControl_CommProtocols.RS485.begin(115200); // Start in receive mode - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); Serial.println("Initialization done!"); } void loop() { - if (comm_protocols.rs485.available()) - Serial.write(comm_protocols.rs485.read()); + if (MachineControl_CommProtocols.RS485.available()) + Serial.write(MachineControl_CommProtocols.RS485.read()); if (millis() > sendNow) { String log = "["; @@ -72,14 +72,14 @@ void loop() Serial.println(log); // Disable receive mode before transmission - comm_protocols.rs485.noReceive(); + MachineControl_CommProtocols.RS485.noReceive(); - comm_protocols.rs485.beginTransmission(); - comm_protocols.rs485.println(msg); - comm_protocols.rs485.endTransmission(); + MachineControl_CommProtocols.RS485.beginTransmission(); + MachineControl_CommProtocols.RS485.println(msg); + MachineControl_CommProtocols.RS485.endTransmission(); // Re-enable receive mode after transmission - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); sendNow = millis() + sendInterval; } diff --git a/examples/RS485_fullduplex/RS485_fullduplex.ino b/examples/RS485_fullduplex/RS485_fullduplex.ino index 2476e06..10cae43 100644 --- a/examples/RS485_fullduplex/RS485_fullduplex.ino +++ b/examples/RS485_fullduplex/RS485_fullduplex.ino @@ -32,24 +32,24 @@ void setup() Serial.println("Start RS485 initialization"); // Set the PMC Communication Protocols to default config - comm_protocols.init(); + MachineControl_CommProtocols.begin(); // RS485/RS232 default config is: // - RS485 mode // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled // Enable the RS485/RS232 system - comm_protocols.rs485Enable(true); + MachineControl_CommProtocols.RS485Enable(); // Enable Full Duplex mode // This will also enable A/B and Y/Z 120 Ohm termination resistors - comm_protocols.rs485FullDuplex(true); + MachineControl_CommProtocols.RS485SetFullDuplex(true); // Specify baudrate, and preamble and postamble times for RS485 communication - comm_protocols.rs485.begin(115200, 0, 500); + MachineControl_CommProtocols.RS485.begin(115200, 0, 500); // Start in receive mode - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); Serial.println("Initialization done!"); @@ -57,22 +57,22 @@ void setup() void loop() { - if (comm_protocols.rs485.available()) - Serial.write(comm_protocols.rs485.read()); + if (MachineControl_CommProtocols.RS485.available()) + Serial.write(MachineControl_CommProtocols.RS485.read()); if (millis() > sendNow) { // Disable receive mode before transmission - comm_protocols.rs485.noReceive(); + MachineControl_CommProtocols.RS485.noReceive(); - comm_protocols.rs485.beginTransmission(); + MachineControl_CommProtocols.RS485.beginTransmission(); - comm_protocols.rs485.print("hello "); - comm_protocols.rs485.println(counter++); + MachineControl_CommProtocols.RS485.print("hello "); + MachineControl_CommProtocols.RS485.println(counter++); - comm_protocols.rs485.endTransmission(); + MachineControl_CommProtocols.RS485.endTransmission(); // Re-enable receive mode after transmission - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); sendNow = millis() + sendInterval; } diff --git a/examples/RS485_halfduplex/RS485_halfduplex.ino b/examples/RS485_halfduplex/RS485_halfduplex.ino index 882313d..871dc6a 100644 --- a/examples/RS485_halfduplex/RS485_halfduplex.ino +++ b/examples/RS485_halfduplex/RS485_halfduplex.ino @@ -33,7 +33,7 @@ void setup() Serial.println("Start RS485 initialization"); // Set the PMC Communication Protocols to default config - comm_protocols.init(); + MachineControl_CommProtocols.begin(); // RS485/RS232 default config is: // - RS485 mode @@ -41,34 +41,34 @@ void setup() // - No A/B and Y/Z 120 Ohm termination enabled // Enable the RS485/RS232 system - comm_protocols.rs485Enable(true); + MachineControl_CommProtocols.RS485Enable(); // Specify baudrate, and preamble and postamble times for RS485 communication - comm_protocols.rs485.begin(115200, 0, 500); + MachineControl_CommProtocols.RS485.begin(115200, 0, 500); // Start in receive mode - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); Serial.println("Initialization done!"); } void loop() { - if (comm_protocols.rs485.available()) - Serial.write(comm_protocols.rs485.read()); + if (MachineControl_CommProtocols.RS485.available()) + Serial.write(MachineControl_CommProtocols.RS485.read()); if (millis() > sendNow) { // Disable receive mode before transmission - comm_protocols.rs485.noReceive(); + MachineControl_CommProtocols.RS485.noReceive(); - comm_protocols.rs485.beginTransmission(); + MachineControl_CommProtocols.RS485.beginTransmission(); - comm_protocols.rs485.print("hello "); - comm_protocols.rs485.println(counter++); + MachineControl_CommProtocols.RS485.print("hello "); + MachineControl_CommProtocols.RS485.println(counter++); - comm_protocols.rs485.endTransmission(); + MachineControl_CommProtocols.RS485.endTransmission(); // Re-enable receive mode after transmission - comm_protocols.rs485.receive(); + MachineControl_CommProtocols.RS485.receive(); sendNow = millis() + sendInterval; } diff --git a/src/COMMClass.cpp b/src/COMMClass.cpp index 96670a6..ce8d1fa 100644 --- a/src/COMMClass.cpp +++ b/src/COMMClass.cpp @@ -1,47 +1,93 @@ +/** + * @file COMMClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the COMMClass used to initialize and interact with communication protocols (CAN Bus, RS485, and RS232) on the Portenta Machine Control board. + * + */ + +/* Includes -----------------------------------------------------------------*/ #include "COMMClass.h" -void COMMClass::init() { - //SHUTDOWN OF RS485 LEDS - digitalWrite(PinNameToIndex(PA_0), LOW); - digitalWrite(PinNameToIndex(PI_9), LOW); - //SHUTDOWN OF CAN LEDS +/* Functions -----------------------------------------------------------------*/ +COMMClass::COMMClass() { + pinMode(PinNameToIndex(PA_13), OUTPUT); //Disable CAN pin + pinMode(PinNameToIndex(PB_8), OUTPUT); + pinMode(PinNameToIndex(PH_13), OUTPUT); + + pinMode(PinNameToIndex(PA_0), OUTPUT); + pinMode(PinNameToIndex(PI_9), OUTPUT); + + pinMode(PinNameToIndex(PG_9), OUTPUT); + pinMode(PinNameToIndex(PA_10), OUTPUT); + pinMode(PinNameToIndex(PI_15), OUTPUT); + pinMode(PinNameToIndex(PI_14), OUTPUT); + pinMode(PinNameToIndex(PG_14), OUTPUT); + pinMode(PinNameToIndex(PA_9), OUTPUT); +} + +COMMClass::~COMMClass() +{ } + +bool COMMClass::begin() { + /* Turn-off LEDs CAN */ digitalWrite(PinNameToIndex(PB_8), HIGH); digitalWrite(PinNameToIndex(PH_13), HIGH); - // SET DEFAULTS for RS485 - rs485Enable(false); - rs485ModeRS232(false); - rs485FullDuplex(false); - rs485YZTerm(false); - rs485ABTerm(false); - rs485Slew(false); + /* Turn-off LEDs RS485 */ + digitalWrite(PinNameToIndex(PA_0), LOW); + digitalWrite(PinNameToIndex(PI_9), LOW); + + /* Set defaults for RS485 */ + RS485Disable(); + RS485SetModeRS232(false); + RS485SetFullDuplex(false); + RS485SetYZTerm(false); + RS485SetABTerm(false); + RS485SetSlew(false); + + return true; } -void COMMClass::enableCAN() { - can_disable = 0; +void COMMClass::CANEnable() { + digitalWrite(PinNameToIndex(PA_13), LOW); } -void COMMClass::disableCAN() { - can_disable = 1; +void COMMClass::CANDisable() { + digitalWrite(PinNameToIndex(PA_13), HIGH); } -void COMMClass::rs485Enable(bool enable) { digitalWrite(PinNameToIndex(PG_9), enable ? HIGH : LOW); } +void COMMClass::RS485Enable() { + digitalWrite(PinNameToIndex(PG_9), HIGH); +} -void COMMClass::rs485ModeRS232(bool enable) { digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); } +void COMMClass::RS485Disable() { + digitalWrite(PinNameToIndex(PG_9), LOW); +} -void COMMClass::rs485YZTerm(bool enable) { digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); } +void COMMClass::RS485SetModeRS232(bool enable) { + digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); +} -void COMMClass::rs485ABTerm(bool enable) { digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); } +void COMMClass::RS485SetYZTerm(bool enable) { + digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); +} + +void COMMClass::RS485SetABTerm(bool enable) { + digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); +} -void COMMClass::rs485Slew(bool enable) { digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); } +void COMMClass::RS485SetSlew(bool enable) { + digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); +} -void COMMClass::rs485FullDuplex(bool enable) { +void COMMClass::RS485SetFullDuplex(bool enable) { digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); if (enable) { // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled - rs485YZTerm(true); - rs485ABTerm(true); + RS485SetYZTerm(true); + RS485SetABTerm(true); } } -COMMClass comm_protocols; \ No newline at end of file +COMMClass MachineControl_CommProtocols; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/COMMClass.h b/src/COMMClass.h index 2c292a9..af7165c 100644 --- a/src/COMMClass.h +++ b/src/COMMClass.h @@ -1,49 +1,123 @@ +/** + * @file COMMClass.h + * @author Leonardo Cavagnis + * @brief Header file for the COMMClass used to initialize and interact with communication protocols (CAN Bus, RS485, and RS232) on the Portenta Machine Control board. + * + * This library provides a class to manage the communication protocols of the Portenta Machine Control board. + * It allows initializing and interacting with the CAN Bus, RS485, and RS232 protocols. The library also initializes the corresponding LEDs for CAN and RS485. + */ + +#ifndef __COMM_CLASS_H +#define __COMM_CLASS_H + +/* Includes -------------------------------------------------------------------*/ #include #include #include #include +/* Class ----------------------------------------------------------------------*/ + /** - * The COMMClass is used to initialize the CAN and RS485 LEDs and - * establish the power mode of the CAN bus. + * @class COMMClass + * @brief Class for managing the communication protocols of the Portenta Machine Control. */ class COMMClass { public: - // to be tested: check if can be made a big pin initialization - - /** - * Shutdown RS485 and CAN LEDs - */ - void init(); - - /** - * Set the CAN transceiver in Normal mode. In this mode, the transceiver - * can transmit and receive data via the bus lines CANH and CANL. - */ - void enableCAN(); - - /** - * Set the CAN transceiver in standby (low power) mode. In this mode the - * transceiver will not be able to transmit or correctly receive data via the bus lines. - * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, - * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) - * bus are reflected on pin RXD. - */ - void disableCAN(); - - void rs485Enable(bool enable); - void rs485ModeRS232(bool enable); - void rs485YZTerm(bool enable); - void rs485ABTerm(bool enable); - void rs485Slew(bool enable); - void rs485FullDuplex(bool enable); - - arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; - mbed::CAN can {PB_8, PH_13}; - RS485Class rs485 {_UART4_, PinNameToIndex(PA_0), PinNameToIndex(PI_13), PinNameToIndex(PI_10)}; - -private: - mbed::DigitalOut can_disable = mbed::DigitalOut(PA_13, 0); + /** + * @brief Construct a COMMClass object. + * + * This constructor initializes a COMMClass object. + */ + COMMClass(); + + /** + * @brief Destruct the COMMClass object. + * + * This destructor releases any resources used by the COMMClass object. + */ + ~COMMClass(); + + /** + * @brief Begin the communication protocols. + * + * This method initializes the communication protocols, including the RS485 and CAN LEDs. + * + * @return true If the initialization is successful, false otherwise. + */ + bool begin(); + + /** + * @brief Set the CAN transceiver in Normal mode. + * + * In this mode, the transceiver can transmit and receive data via the bus lines CANH and CANL. + */ + void CANEnable(); + + /** + * @brief Set the CAN transceiver in Standby (low power) mode. + * + * In this mode, the transceiver will not be able to transmit or correctly receive data via the bus lines. + * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, + * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) + * bus are reflected on pin RXD. + */ + void CANDisable(); + + /** + * @brief Enable RS485 communication. + * + * This method enables RS485 communication. + */ + void RS485Enable(); + + /** + * @brief Disable RS485 communication. + * + * This method disables RS485 communication. + */ + void RS485Disable(); + + /** + * @brief Set RS485 mode to RS232. + * + * @param enable If true, sets the RS485 mode to RS232, else sets to RS485 mode. + */ + void RS485SetModeRS232(bool enable); + + /** + * @brief Set YZ termination for RS485 communication. + * + * @param enable If true, enables YZ termination, else disables it. + */ + void RS485SetYZTerm(bool enable); + + /** + * @brief Set AB termination for RS485 communication. + * + * @param enable If true, enables AB termination, else disables it. + */ + void RS485SetABTerm(bool enable); + + /** + * @brief Set the slew rate for RS485 communication. + * + * @param enable If true, enables the slew rate control, else disables it. + */ + void RS485SetSlew(bool enable); + + /** + * @brief Set RS485 communication to Full Duplex mode. + * + * @param enable If true, sets RS485 communication to Full Duplex mode, else to Half Duplex mode. + */ + void RS485SetFullDuplex(bool enable); + + arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; + mbed::CAN CAN {PB_8, PH_13}; + RS485Class RS485 {_UART4_, PinNameToIndex(PA_0), PinNameToIndex(PI_13), PinNameToIndex(PI_10)}; }; -extern COMMClass comm_protocols; \ No newline at end of file +extern COMMClass MachineControl_CommProtocols; + +#endif /* __COMM_CLASS_H */ \ No newline at end of file From cee0a68e6906b53327b030d929361066107b63f2 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 28 Jul 2023 13:03:45 +0200 Subject: [PATCH 21/47] docs: update --- src/AnalogInClass.cpp | 1 - src/AnalogInClass.h | 13 ++++++++++--- src/AnalogOutClass.cpp | 1 - src/AnalogOutClass.h | 15 +++++++++++---- src/DigitalOutputsClass.h | 28 ++++++++++++++++++---------- src/ProgrammableDINClass.h | 38 +++++++++++++++++++++++--------------- src/ProgrammableDIOClass.h | 8 +++++++- src/TempProbesClass.h | 6 ++++++ 8 files changed, 75 insertions(+), 35 deletions(-) diff --git a/src/AnalogInClass.cpp b/src/AnalogInClass.cpp index c43518a..bc529b6 100644 --- a/src/AnalogInClass.cpp +++ b/src/AnalogInClass.cpp @@ -140,5 +140,4 @@ uint16_t AnalogInClass::read(int channel) { } AnalogInClass MachineControl_AnalogIn; - /**** END OF FILE ****/ \ No newline at end of file diff --git a/src/AnalogInClass.h b/src/AnalogInClass.h index 54e2795..5d1dca3 100644 --- a/src/AnalogInClass.h +++ b/src/AnalogInClass.h @@ -6,6 +6,7 @@ * This library allows to set the resistor configuration for the type of connected analog sensor (0-10V, 4-20mA or NTC) * and to capture the analog values acquired by the ANALOG IN channels. */ + #ifndef __ANALOGIN_CLASS_H #define __ANALOGIN_CLASS_H @@ -36,6 +37,12 @@ class AnalogInClass { * @param ai2_pin The analog pin number of the channel 2 */ AnalogInClass(PinName ai0_pin = PC_3C, PinName ai1_pin = PC_2C, PinName ai2_pin = PA_1C); + + /** + * @brief Destruct the AnalogInClass object. + * + * This destructor releases any resources used by the AnalogInClass object. + */ ~AnalogInClass(); /** @@ -56,9 +63,9 @@ class AnalogInClass { uint16_t read(int channel); private: - PinName _ai0; - PinName _ai1; - PinName _ai2; + PinName _ai0; // Analog input pin for channel 0 + PinName _ai1; // Analog input pin for channel 1 + PinName _ai2; // Analog input pin for channel 2 }; extern AnalogInClass MachineControl_AnalogIn; diff --git a/src/AnalogOutClass.cpp b/src/AnalogOutClass.cpp index e6674c0..9e1d77f 100644 --- a/src/AnalogOutClass.cpp +++ b/src/AnalogOutClass.cpp @@ -70,5 +70,4 @@ void AnalogOutClass::write(int channel, float voltage) { } AnalogOutClass MachineControl_AnalogOut; - /**** END OF FILE ****/ \ No newline at end of file diff --git a/src/AnalogOutClass.h b/src/AnalogOutClass.h index a22956d..e4a9710 100644 --- a/src/AnalogOutClass.h +++ b/src/AnalogOutClass.h @@ -5,6 +5,7 @@ * * This library allows to configure the analog channels as PWM, to set frequency and value. */ + #ifndef __ANALOGOUT_CLASS_H #define __ANALOGOUT_CLASS_H @@ -29,6 +30,12 @@ class AnalogOutClass { * @param ao3_pin The analog pin number of the channel 2 */ AnalogOutClass(PinName ao0_pin = PJ_11, PinName ao1_pin = PK_1, PinName ao2_pin = PG_7, PinName ao3_pin = PC_7); + + /** + * @brief Destruct the AnalogOutClass object. + * + * This destructor releases any resources used by the AnalogOutClass object. + */ ~AnalogOutClass(); /** @@ -55,10 +62,10 @@ class AnalogOutClass { void write(int channel, float voltage); private: - mbed::PwmOut _ao0; - mbed::PwmOut _ao1; - mbed::PwmOut _ao2; - mbed::PwmOut _ao3; + mbed::PwmOut _ao0; // PWM output for Analog Out channel 0 + mbed::PwmOut _ao1; // PWM output for Analog Out channel 1 + mbed::PwmOut _ao2; // PWM output for Analog Out channel 2 + mbed::PwmOut _ao3; // PWM output for Analog Out channel 3 }; extern AnalogOutClass MachineControl_AnalogOut; diff --git a/src/DigitalOutputsClass.h b/src/DigitalOutputsClass.h index b08a0de..301dbc3 100644 --- a/src/DigitalOutputsClass.h +++ b/src/DigitalOutputsClass.h @@ -5,6 +5,7 @@ * * This library allows to interface with the IO Expander and set the digital outputs. */ + #ifndef __DIGITALOUTPUTS_CLASS_H #define __DIGITALOUTPUTS_CLASS_H @@ -44,6 +45,12 @@ class DigitalOutputsClass { PinName do6_pin = PD_3, PinName do7_pin = PA_14, PinName latch_pin = PB_2); + + /** + * @brief Destruct the DigitalOutputsClass object. + * + * This destructor releases any resources used by the DigitalOutputsClass object. + */ ~DigitalOutputsClass(); /** @@ -71,16 +78,17 @@ class DigitalOutputsClass { * - To set all channels to LOW: val_mask = 0 (0b00000000) */ void writeAll(uint8_t val_mask); -private: - PinName _do0; - PinName _do1; - PinName _do2; - PinName _do3; - PinName _do4; - PinName _do5; - PinName _do6; - PinName _do7; - PinName _latch; + + private: + PinName _do0; // Digital output pin for DO (Digital Out) channel 0 + PinName _do1; // Digital output pin for DO (Digital Out) channel 1 + PinName _do2; // Digital output pin for DO (Digital Out) channel 2 + PinName _do3; // Digital output pin for DO (Digital Out) channel 3 + PinName _do4; // Digital output pin for DO (Digital Out) channel 4 + PinName _do5; // Digital output pin for DO (Digital Out) channel 5 + PinName _do6; // Digital output pin for DO (Digital Out) channel 6 + PinName _do7; // Digital output pin for DO (Digital Out) channel 7 + PinName _latch; // Latch control pin /** * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. diff --git a/src/ProgrammableDINClass.h b/src/ProgrammableDINClass.h index 84cc981..0bb6159 100644 --- a/src/ProgrammableDINClass.h +++ b/src/ProgrammableDINClass.h @@ -23,21 +23,29 @@ * This class extends the ArduinoIOExpanderClass to interface with the IO Expander and provides methods to configure digital inputs. */ class ProgrammableDINClass : public ArduinoIOExpanderClass { -public: - /** - * @brief Construct a ProgrammableDINClass object. - */ - ProgrammableDINClass(); - ~ProgrammableDINClass(); - - /** - * @brief Initialize the ProgrammableDIN module. - * - * Test connection with the IOExpander and set all the pins to the default mode. - * - * @return true If the ProgrammableDIN module is successfully initialized, false otherwise. - */ - bool begin(); + public: + /** + * @brief Construct a ProgrammableDINClass object. + * + * This constructor initializes a ProgrammableDINClass object. + */ + ProgrammableDINClass(); + + /** + * @brief Destruct the ProgrammableDINClass object. + * + * This destructor releases any resources used by the ProgrammableDINClass object. + */ + ~ProgrammableDINClass(); + + /** + * @brief Initialize the ProgrammableDIN module. + * + * Test connection with the IOExpander and set all the pins to the default mode. + * + * @return true If the ProgrammableDIN module is successfully initialized, false otherwise. + */ + bool begin(); }; extern ProgrammableDINClass MachineControl_DigitalInputs; diff --git a/src/ProgrammableDIOClass.h b/src/ProgrammableDIOClass.h index 987fab0..a3b3c35 100644 --- a/src/ProgrammableDIOClass.h +++ b/src/ProgrammableDIOClass.h @@ -32,6 +32,12 @@ class ProgrammableDIOClass : public ArduinoIOExpanderClass { * @param latch_pin The pin number for the latch mode control. */ ProgrammableDIOClass(PinName latch_pin = PH_14); + + /** + * @brief Destruct the ProgrammableDIOClass object. + * + * This destructor releases any resources used by the ProgrammableDIOClass object. + */ ~ProgrammableDIOClass(); /** @@ -43,7 +49,7 @@ class ProgrammableDIOClass : public ArduinoIOExpanderClass { bool begin(bool latch_mode = true); private: - PinName _latch; + PinName _latch; // Latch control pin /** * @brief Configures the thermal shutdown of the high-side switches (TPS4H160) to operate in latch mode. diff --git a/src/TempProbesClass.h b/src/TempProbesClass.h index 54a1c96..238f417 100644 --- a/src/TempProbesClass.h +++ b/src/TempProbesClass.h @@ -43,6 +43,12 @@ class TempProbesClass { * @param rtd_th_pin The pin number for the RTD connection. */ TempProbesClass(PinName ch_sel0_pin = PD_6, PinName ch_sel1_pin = PI_4, PinName ch_sel2_pin = PG_10, PinName rtd_th_pin = PC_15); + + /** + * @brief Destruct the TempProbesClass object. + * + * This destructor releases any resources used by the TempProbesClass object. + */ ~TempProbesClass(); /** From 01d47038228c05f8d5d5dbc7c509ba910156f424 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 1 Aug 2023 11:36:42 +0200 Subject: [PATCH 22/47] create two different classes for the comm protocol: CAN (CANCommClass) and RSx (RS485CommClass) --- examples/CAN/ReadCan/ReadCan.ino | 8 +- examples/CAN/WriteCan/WriteCan.ino | 11 +- examples/RS232/RS232.ino | 28 ++-- .../RS485_fullduplex/RS485_fullduplex.ino | 28 ++-- .../RS485_halfduplex/RS485_halfduplex.ino | 27 ++-- src/Arduino_MachineControl.h | 3 +- src/CANCommClass.cpp | 41 ++++++ src/CANCommClass.h | 84 ++++++++++++ src/COMMClass.cpp | 93 ------------- src/COMMClass.h | 123 ------------------ src/RS485CommClass.cpp | 96 ++++++++++++++ src/RS485CommClass.h | 112 ++++++++++++++++ 12 files changed, 376 insertions(+), 278 deletions(-) create mode 100644 src/CANCommClass.cpp create mode 100644 src/CANCommClass.h delete mode 100644 src/COMMClass.cpp delete mode 100644 src/COMMClass.h create mode 100644 src/RS485CommClass.cpp create mode 100644 src/RS485CommClass.h diff --git a/examples/CAN/ReadCan/ReadCan.ino b/examples/CAN/ReadCan/ReadCan.ino index 7aa847d..e34eb26 100644 --- a/examples/CAN/ReadCan/ReadCan.ino +++ b/examples/CAN/ReadCan/ReadCan.ino @@ -10,7 +10,6 @@ */ #include -#include #define DATARATE_2MB 2000000 #define DATARATE_1_5MB 1500000 @@ -24,16 +23,14 @@ void setup() { } Serial.println("Start CAN initialization"); - MachineControl_CommProtocols.begin(); - MachineControl_CommProtocols.CANEnable(); + MachineControl_CANComm.begin(DATARATE_800KB); - MachineControl_CommProtocols.CAN.frequency(DATARATE_800KB); Serial.println("Initialization done"); } void loop() { mbed::CANMessage msg; - if (MachineControl_CommProtocols.CAN.read(msg)) { + if (MachineControl_CANComm.read(msg)) { // Print the sender ID Serial.print("ID: "); @@ -42,7 +39,6 @@ void loop() { // Print the first Payload Byte Serial.print("Message received:"); Serial.println(msg.data[0], DEC); - } delay(100); diff --git a/examples/CAN/WriteCan/WriteCan.ino b/examples/CAN/WriteCan/WriteCan.ino index e32b9b0..f5d0ab3 100644 --- a/examples/CAN/WriteCan/WriteCan.ino +++ b/examples/CAN/WriteCan/WriteCan.ino @@ -10,7 +10,6 @@ */ #include -#include #define DATARATE_2MB 2000000 #define DATARATE_1_5MB 1500000 @@ -25,9 +24,7 @@ void setup() { Serial.println("Start CAN initialization"); - MachineControl_CommProtocols.begin(); - MachineControl_CommProtocols.CANEnable(); - MachineControl_CommProtocols.CAN.frequency(DATARATE_800KB); + MachineControl_CANComm.begin(DATARATE_800KB); Serial.println("Initialization done"); } @@ -38,12 +35,12 @@ int payload_size = 1; void loop() { mbed::CANMessage msg = mbed::CANMessage(13ul, &payload, payload_size); - if (MachineControl_CommProtocols.CAN.write(msg)) { + if (MachineControl_CANComm.write(msg)) { Serial.println("Message sent"); } else { Serial.println("Transmission Error: "); - Serial.println(MachineControl_CommProtocols.CAN.tderror()); - MachineControl_CommProtocols.CAN.reset(); + Serial.println(MachineControl_CANComm.tderror()); + MachineControl_CANComm.reset(); } delay(100); diff --git a/examples/RS232/RS232.ino b/examples/RS232/RS232.ino index 5875e58..cafca98 100644 --- a/examples/RS232/RS232.ino +++ b/examples/RS232/RS232.ino @@ -33,32 +33,28 @@ void setup() delay(2500); Serial.println("Start RS232 initialization"); - // Set the PMC Communication Protocols to default config - MachineControl_CommProtocols.begin(); - + // Set the PMC Communication Protocols to default config and enable the RS485/RS232 system // RS485/RS232 default config is: // - RS485/RS232 system disabled // - RS485 mode // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled + // Specify baudrate for the communication + MachineControl_RS485Comm.begin(115200); - // Enable the RS485/RS232 system - MachineControl_CommProtocols.RS485Enable(); // Enable the RS232 mode - MachineControl_CommProtocols.RS485SetModeRS232(true); + MachineControl_RS485Comm.setModeRS232(true); - // Specify baudrate for RS232 communication - MachineControl_CommProtocols.RS485.begin(115200); // Start in receive mode - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); Serial.println("Initialization done!"); } void loop() { - if (MachineControl_CommProtocols.RS485.available()) - Serial.write(MachineControl_CommProtocols.RS485.read()); + if (MachineControl_RS485Comm.available()) + Serial.write(MachineControl_RS485Comm.read()); if (millis() > sendNow) { String log = "["; @@ -72,14 +68,14 @@ void loop() Serial.println(log); // Disable receive mode before transmission - MachineControl_CommProtocols.RS485.noReceive(); + MachineControl_RS485Comm.noReceive(); - MachineControl_CommProtocols.RS485.beginTransmission(); - MachineControl_CommProtocols.RS485.println(msg); - MachineControl_CommProtocols.RS485.endTransmission(); + MachineControl_RS485Comm.beginTransmission(); + MachineControl_RS485Comm.println(msg); + MachineControl_RS485Comm.endTransmission(); // Re-enable receive mode after transmission - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); sendNow = millis() + sendInterval; } diff --git a/examples/RS485_fullduplex/RS485_fullduplex.ino b/examples/RS485_fullduplex/RS485_fullduplex.ino index 10cae43..6d1dfcf 100644 --- a/examples/RS485_fullduplex/RS485_fullduplex.ino +++ b/examples/RS485_fullduplex/RS485_fullduplex.ino @@ -32,24 +32,20 @@ void setup() Serial.println("Start RS485 initialization"); // Set the PMC Communication Protocols to default config - MachineControl_CommProtocols.begin(); // RS485/RS232 default config is: // - RS485 mode // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled - // Enable the RS485/RS232 system - MachineControl_CommProtocols.RS485Enable(); + // Specify baudrate, and preamble and postamble times for RS485 communication + MachineControl_RS485Comm.begin(115200, 0, 500); // Enable Full Duplex mode // This will also enable A/B and Y/Z 120 Ohm termination resistors - MachineControl_CommProtocols.RS485SetFullDuplex(true); - - // Specify baudrate, and preamble and postamble times for RS485 communication - MachineControl_CommProtocols.RS485.begin(115200, 0, 500); + MachineControl_RS485Comm.setFullDuplex(true); // Start in receive mode - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); Serial.println("Initialization done!"); @@ -57,22 +53,22 @@ void setup() void loop() { - if (MachineControl_CommProtocols.RS485.available()) - Serial.write(MachineControl_CommProtocols.RS485.read()); + if (MachineControl_RS485Comm.available()) + Serial.write(MachineControl_RS485Comm.read()); if (millis() > sendNow) { // Disable receive mode before transmission - MachineControl_CommProtocols.RS485.noReceive(); + MachineControl_RS485Comm.noReceive(); - MachineControl_CommProtocols.RS485.beginTransmission(); + MachineControl_RS485Comm.beginTransmission(); - MachineControl_CommProtocols.RS485.print("hello "); - MachineControl_CommProtocols.RS485.println(counter++); + MachineControl_RS485Comm.print("hello "); + MachineControl_RS485Comm.println(counter++); - MachineControl_CommProtocols.RS485.endTransmission(); + MachineControl_RS485Comm.endTransmission(); // Re-enable receive mode after transmission - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); sendNow = millis() + sendInterval; } diff --git a/examples/RS485_halfduplex/RS485_halfduplex.ino b/examples/RS485_halfduplex/RS485_halfduplex.ino index 871dc6a..28517d6 100644 --- a/examples/RS485_halfduplex/RS485_halfduplex.ino +++ b/examples/RS485_halfduplex/RS485_halfduplex.ino @@ -23,7 +23,6 @@ unsigned long counter { 0 }; void setup() { - Serial.begin(115200); // Wait for Serial or start after 2.5s for (auto const timeout = millis() + 2500; !Serial && timeout < millis(); delay(500)) @@ -33,42 +32,38 @@ void setup() Serial.println("Start RS485 initialization"); // Set the PMC Communication Protocols to default config - MachineControl_CommProtocols.begin(); - // RS485/RS232 default config is: // - RS485 mode // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled - // Enable the RS485/RS232 system - MachineControl_CommProtocols.RS485Enable(); - // Specify baudrate, and preamble and postamble times for RS485 communication - MachineControl_CommProtocols.RS485.begin(115200, 0, 500); + MachineControl_RS485Comm.begin(115200, 0, 500); + // Start in receive mode - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); Serial.println("Initialization done!"); } void loop() { - if (MachineControl_CommProtocols.RS485.available()) - Serial.write(MachineControl_CommProtocols.RS485.read()); + if (MachineControl_RS485Comm.available()) + Serial.write(MachineControl_RS485Comm.read()); if (millis() > sendNow) { // Disable receive mode before transmission - MachineControl_CommProtocols.RS485.noReceive(); + MachineControl_RS485Comm.noReceive(); - MachineControl_CommProtocols.RS485.beginTransmission(); + MachineControl_RS485Comm.beginTransmission(); - MachineControl_CommProtocols.RS485.print("hello "); - MachineControl_CommProtocols.RS485.println(counter++); + MachineControl_RS485Comm.print("hello "); + MachineControl_RS485Comm.println(counter++); - MachineControl_CommProtocols.RS485.endTransmission(); + MachineControl_RS485Comm.endTransmission(); // Re-enable receive mode after transmission - MachineControl_CommProtocols.RS485.receive(); + MachineControl_RS485Comm.receive(); sendNow = millis() + sendInterval; } diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index 4ed792e..909f6e7 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -10,6 +10,7 @@ #include "RtcControllerClass.h" #include "USBClass.h" #include "EncoderClass.h" -#include "COMMClass.h" +#include "CANCommClass.h" +#include "RS485CommClass.h" #endif /* __ARDUINO_MACHINE_CONTROL_H */ diff --git a/src/CANCommClass.cpp b/src/CANCommClass.cpp new file mode 100644 index 0000000..1c94c33 --- /dev/null +++ b/src/CANCommClass.cpp @@ -0,0 +1,41 @@ +/** + * @file CANCommClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the CANCommClass used to initialize and interact with the CAN Bus communication protocol on the Portenta Machine Control board. + */ + +/* Includes -----------------------------------------------------------------*/ +#include "CANCommClass.h" + +/* Functions -----------------------------------------------------------------*/ +CANCommClass::CANCommClass(PinName can_tx_pin, PinName can_rx_pin) : + mbed::CAN(can_tx_pin, can_rx_pin) +{ } + +CANCommClass::~CANCommClass() +{ } + +bool CANCommClass::begin(int can_bitrate) { + pinMode(PinNameToIndex(PA_13), OUTPUT); //Disable CAN pin + pinMode(PinNameToIndex(PB_8), OUTPUT); + pinMode(PinNameToIndex(PH_13), OUTPUT); + + _enable(); + + return mbed::CAN::frequency(can_bitrate); +} + +void CANCommClass::end() { + _disable(); +} + +void CANCommClass::_enable() { + digitalWrite(PinNameToIndex(PA_13), LOW); +} + +void CANCommClass::_disable() { + digitalWrite(PinNameToIndex(PA_13), HIGH); +} + +CANCommClass MachineControl_CANComm; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/CANCommClass.h b/src/CANCommClass.h new file mode 100644 index 0000000..3d428d0 --- /dev/null +++ b/src/CANCommClass.h @@ -0,0 +1,84 @@ +/** + * @file CANCommClass.h + * @author Leonardo Cavagnis + * @brief Header file for the CANCommClass used to initialize and interact with the CAN Bus communication protocol on the Portenta Machine Control board. + * + * This library provides a class to manage the CAN Bus communication protocol of the Portenta Machine Control board. + * It allows initializing and interacting with the CAN Bus protocol. The library also initializes the corresponding LED for CAN. + */ + +#ifndef __CAN_COMM_CLASS_H +#define __CAN_COMM_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class CANCommClass + * @brief Class for managing the CAN Bus communication protocol of the Portenta Machine Control. + * + * The `CANCommClass` is a subclass of `mbed::CAN` and provides methods to work with the CAN Bus communication protocol on the Portenta Machine Control board. + * It includes initialization of the corresponding LED for CAN. + */ +class CANCommClass: public mbed::CAN { + public: + /** + * @brief Construct a CANCommClass object. + * + * This constructor initializes a CANCommClass object with the specified CAN_TX and CAN_RX pins. + * + * @param can_tx_pin The pin for transmitting data on the CAN Bus. + * @param can_rx_pin The pin for receiving data on the CAN Bus. + */ + CANCommClass(PinName can_tx_pin = PB_8, PinName can_rx_pin = PH_13); + + /** + * @brief Destruct the CANCommClass object. + * + * This destructor releases any resources used by the CANCommClass object. + */ + ~CANCommClass(); + + /** + * @brief Begin the CAN communication protocol. + * + * This method initializes the CAN communication protocol, including the corresponding LED for CAN. + * + * @param can_bitrate The desired bitrate for the CAN communication protocol. + * @return true If the initialization is successful, false otherwise. + */ + bool begin(int can_bitrate); + + /** + * @brief Close the CAN communication protocol. + * + * This method de-initializes the CAN communication protocol, stopping communication on the CAN Bus. + */ + void end(); + + private: + /** + * @brief Set the CAN transceiver in Normal mode. + * + * In this mode, the CAN transceiver can transmit and receive data via the bus lines CANH and CANL. + */ + void _enable(); + + /** + * @brief Set the CAN transceiver in Standby (low power) mode. + * + * In this mode, the CAN transceiver will not be able to transmit or correctly receive data via the bus lines. + * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, + * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) + * bus are reflected on pin RXD. + */ + void _disable(); +}; + +extern CANCommClass MachineControl_CANComm; + +#endif /* __CAN_COMM_CLASS_H */ \ No newline at end of file diff --git a/src/COMMClass.cpp b/src/COMMClass.cpp deleted file mode 100644 index ce8d1fa..0000000 --- a/src/COMMClass.cpp +++ /dev/null @@ -1,93 +0,0 @@ -/** - * @file COMMClass.cpp - * @author Leonardo Cavagnis - * @brief Source file for the COMMClass used to initialize and interact with communication protocols (CAN Bus, RS485, and RS232) on the Portenta Machine Control board. - * - */ - -/* Includes -----------------------------------------------------------------*/ -#include "COMMClass.h" - -/* Functions -----------------------------------------------------------------*/ -COMMClass::COMMClass() { - pinMode(PinNameToIndex(PA_13), OUTPUT); //Disable CAN pin - pinMode(PinNameToIndex(PB_8), OUTPUT); - pinMode(PinNameToIndex(PH_13), OUTPUT); - - pinMode(PinNameToIndex(PA_0), OUTPUT); - pinMode(PinNameToIndex(PI_9), OUTPUT); - - pinMode(PinNameToIndex(PG_9), OUTPUT); - pinMode(PinNameToIndex(PA_10), OUTPUT); - pinMode(PinNameToIndex(PI_15), OUTPUT); - pinMode(PinNameToIndex(PI_14), OUTPUT); - pinMode(PinNameToIndex(PG_14), OUTPUT); - pinMode(PinNameToIndex(PA_9), OUTPUT); -} - -COMMClass::~COMMClass() -{ } - -bool COMMClass::begin() { - /* Turn-off LEDs CAN */ - digitalWrite(PinNameToIndex(PB_8), HIGH); - digitalWrite(PinNameToIndex(PH_13), HIGH); - - /* Turn-off LEDs RS485 */ - digitalWrite(PinNameToIndex(PA_0), LOW); - digitalWrite(PinNameToIndex(PI_9), LOW); - - /* Set defaults for RS485 */ - RS485Disable(); - RS485SetModeRS232(false); - RS485SetFullDuplex(false); - RS485SetYZTerm(false); - RS485SetABTerm(false); - RS485SetSlew(false); - - return true; -} - -void COMMClass::CANEnable() { - digitalWrite(PinNameToIndex(PA_13), LOW); -} - -void COMMClass::CANDisable() { - digitalWrite(PinNameToIndex(PA_13), HIGH); -} - -void COMMClass::RS485Enable() { - digitalWrite(PinNameToIndex(PG_9), HIGH); -} - -void COMMClass::RS485Disable() { - digitalWrite(PinNameToIndex(PG_9), LOW); -} - -void COMMClass::RS485SetModeRS232(bool enable) { - digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); -} - -void COMMClass::RS485SetYZTerm(bool enable) { - digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); -} - -void COMMClass::RS485SetABTerm(bool enable) { - digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); -} - -void COMMClass::RS485SetSlew(bool enable) { - digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); -} - -void COMMClass::RS485SetFullDuplex(bool enable) { - digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); - if (enable) { - // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled - RS485SetYZTerm(true); - RS485SetABTerm(true); - } -} - -COMMClass MachineControl_CommProtocols; -/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/COMMClass.h b/src/COMMClass.h deleted file mode 100644 index af7165c..0000000 --- a/src/COMMClass.h +++ /dev/null @@ -1,123 +0,0 @@ -/** - * @file COMMClass.h - * @author Leonardo Cavagnis - * @brief Header file for the COMMClass used to initialize and interact with communication protocols (CAN Bus, RS485, and RS232) on the Portenta Machine Control board. - * - * This library provides a class to manage the communication protocols of the Portenta Machine Control board. - * It allows initializing and interacting with the CAN Bus, RS485, and RS232 protocols. The library also initializes the corresponding LEDs for CAN and RS485. - */ - -#ifndef __COMM_CLASS_H -#define __COMM_CLASS_H - -/* Includes -------------------------------------------------------------------*/ -#include -#include -#include -#include - -/* Class ----------------------------------------------------------------------*/ - -/** - * @class COMMClass - * @brief Class for managing the communication protocols of the Portenta Machine Control. - */ -class COMMClass { -public: - /** - * @brief Construct a COMMClass object. - * - * This constructor initializes a COMMClass object. - */ - COMMClass(); - - /** - * @brief Destruct the COMMClass object. - * - * This destructor releases any resources used by the COMMClass object. - */ - ~COMMClass(); - - /** - * @brief Begin the communication protocols. - * - * This method initializes the communication protocols, including the RS485 and CAN LEDs. - * - * @return true If the initialization is successful, false otherwise. - */ - bool begin(); - - /** - * @brief Set the CAN transceiver in Normal mode. - * - * In this mode, the transceiver can transmit and receive data via the bus lines CANH and CANL. - */ - void CANEnable(); - - /** - * @brief Set the CAN transceiver in Standby (low power) mode. - * - * In this mode, the transceiver will not be able to transmit or correctly receive data via the bus lines. - * The wake-up filter on the output of the low-power receiver does not latch bus dominant states, - * but ensures that only bus dominant and bus recessive states that persist longer than tfltr(wake) - * bus are reflected on pin RXD. - */ - void CANDisable(); - - /** - * @brief Enable RS485 communication. - * - * This method enables RS485 communication. - */ - void RS485Enable(); - - /** - * @brief Disable RS485 communication. - * - * This method disables RS485 communication. - */ - void RS485Disable(); - - /** - * @brief Set RS485 mode to RS232. - * - * @param enable If true, sets the RS485 mode to RS232, else sets to RS485 mode. - */ - void RS485SetModeRS232(bool enable); - - /** - * @brief Set YZ termination for RS485 communication. - * - * @param enable If true, enables YZ termination, else disables it. - */ - void RS485SetYZTerm(bool enable); - - /** - * @brief Set AB termination for RS485 communication. - * - * @param enable If true, enables AB termination, else disables it. - */ - void RS485SetABTerm(bool enable); - - /** - * @brief Set the slew rate for RS485 communication. - * - * @param enable If true, enables the slew rate control, else disables it. - */ - void RS485SetSlew(bool enable); - - /** - * @brief Set RS485 communication to Full Duplex mode. - * - * @param enable If true, sets RS485 communication to Full Duplex mode, else to Half Duplex mode. - */ - void RS485SetFullDuplex(bool enable); - - arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; - mbed::CAN CAN {PB_8, PH_13}; - RS485Class RS485 {_UART4_, PinNameToIndex(PA_0), PinNameToIndex(PI_13), PinNameToIndex(PI_10)}; -}; - -extern COMMClass MachineControl_CommProtocols; - -#endif /* __COMM_CLASS_H */ \ No newline at end of file diff --git a/src/RS485CommClass.cpp b/src/RS485CommClass.cpp new file mode 100644 index 0000000..a55872d --- /dev/null +++ b/src/RS485CommClass.cpp @@ -0,0 +1,96 @@ +/** + * @file RS485CommClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the RS485CommClass used to initialize and interact with RS485 and RS232 communication protocols on the Portenta Machine Control board. + * + */ + +/* Includes -----------------------------------------------------------------*/ +#include "RS485CommClass.h" +#include + +/* Functions -----------------------------------------------------------------*/ + +RS485CommClass::RS485CommClass(arduino::UART uart_itf, PinName rs_tx_pin, PinName rs_de_pin, PinName rs_re_pin) + : RS485Class(uart_itf, PinNameToIndex(rs_tx_pin), PinNameToIndex(rs_de_pin), PinNameToIndex(rs_re_pin)) +{ } + +RS485CommClass::~RS485CommClass() +{ } + +void RS485CommClass::begin(unsigned long baudrate, int predelay, int postdelay) { + /* Pinout configuration */ + pinMode(PinNameToIndex(PA_0), OUTPUT); + pinMode(PinNameToIndex(PI_9), OUTPUT); + + pinMode(PinNameToIndex(PG_9), OUTPUT); + pinMode(PinNameToIndex(PA_10), OUTPUT); + pinMode(PinNameToIndex(PI_15), OUTPUT); + pinMode(PinNameToIndex(PI_14), OUTPUT); + pinMode(PinNameToIndex(PG_14), OUTPUT); + pinMode(PinNameToIndex(PA_9), OUTPUT); + + /* Turn-off LEDs RS485 */ + digitalWrite(PinNameToIndex(PA_0), LOW); + digitalWrite(PinNameToIndex(PI_9), LOW); + + /* Set defaults for RS485 */ + _disable(); + setModeRS232(false); + setFullDuplex(false); + setYZTerm(false); + setABTerm(false); + setSlew(false); + + /* Enable RS485 communication */ + _enable(); + + /* Call begin() base class to initialize RS485 communication */ + RS485Class::begin(baudrate, predelay, postdelay); + + return; +} + +void RS485CommClass::end() { + _disable(); + + /* Call end() base class to de-initialize RS485 communication */ + RS485Class::end(); +} + +void RS485CommClass::setModeRS232(bool enable) { + digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); +} + +void RS485CommClass::setYZTerm(bool enable) { + digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); +} + +void RS485CommClass::setABTerm(bool enable) { + digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); +} + +void RS485CommClass::setSlew(bool enable) { + digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); +} + +void RS485CommClass::setFullDuplex(bool enable) { + digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); + if (enable) { + // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled + setYZTerm(true); + setABTerm(true); + } +} + +void RS485CommClass::_enable() { + digitalWrite(PinNameToIndex(PG_9), HIGH); +} + +void RS485CommClass::_disable() { + digitalWrite(PinNameToIndex(PG_9), LOW); +} + +arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; +RS485CommClass MachineControl_RS485Comm(_UART4_); +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/RS485CommClass.h b/src/RS485CommClass.h new file mode 100644 index 0000000..ef4b80c --- /dev/null +++ b/src/RS485CommClass.h @@ -0,0 +1,112 @@ +/** + * @file COMMClass.h + * @author Leonardo Cavagnis + * @brief Header file for the RS485CommClass used to initialize and interact with RS485 and RS232 communication protocols on the Portenta Machine Control board. + * + * This library provides a class to manage the RS485 and RS234 protocols of the Portenta Machine Control board. + * It allows initializing and interacting with the serial protocols. The library also initializes the corresponding LEDs. + */ + +#ifndef __RS485_COMM_CLASS_H +#define __RS485_COMM_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class RS485CommClass + * @brief Class for managing the RS485 and RS232 protocols of the Portenta Machine Control. + */ + +class RS485CommClass : public RS485Class { + public: + /** + * @brief Construct a RS485CommClass object. + * + * This constructor initializes a RS485CommClass object. + */ + RS485CommClass(arduino::UART uart_itf, PinName rs_tx_pin = PA_0, PinName rs_de_pin = PI_13, PinName rs_re_pin = PI_10); + + /** + * @brief Destruct the RS485CommClass object. + * + * This destructor releases any resources used by the RS485CommClass object. + */ + ~RS485CommClass(); + + /** + * @brief Begin the RS485 communication protocol. + * + * This method initializes the RS485 communication protocols + * + * @todo ////PARAMETERS + * + * @return true If the initialization is successful, false otherwise. + */ + void begin(unsigned long baudrate = 115200, int predelay = RS485_DEFAULT_PRE_DELAY, int postdelay = RS485_DEFAULT_POST_DELAY); + + /** + * @brief Close the RS485 communication protocol. + * + * This method de-initializes the RS485 communication protocol + */ + void end(); + + /** + * @brief Set RS485 mode to RS232. + * + * @param enable If true, sets the RS485 mode to RS232, else sets to RS485 mode. + */ + void setModeRS232(bool enable); + + /** + * @brief Set YZ termination for RS485 communication. + * + * @param enable If true, enables YZ termination, else disables it. + */ + void setYZTerm(bool enable); + + /** + * @brief Set AB termination for RS485 communication. + * + * @param enable If true, enables AB termination, else disables it. + */ + void setABTerm(bool enable); + + /** + * @brief Set the slew rate for RS485 communication. + * + * @param enable If true, enables the slew rate control, else disables it. + */ + void setSlew(bool enable); + + /** + * @brief Set RS485 communication to Full Duplex mode. + * + * @param enable If true, sets RS485 communication to Full Duplex mode, else to Half Duplex mode. + */ + void setFullDuplex(bool enable); + + private: + /** + * @brief Enable RS485 communication. + * + * This method enables RS485 communication. + */ + void _enable(); + + /** + * @brief Disable RS485 communication. + * + * This method disables RS485 communication. + */ + void _disable(); +}; + +extern RS485CommClass MachineControl_RS485Comm; + +#endif /* __RS485_COMM_CLASS_H */ \ No newline at end of file From 30609f8c158b8f0e153bd6c523dafa587e196578 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 1 Aug 2023 12:57:30 +0200 Subject: [PATCH 23/47] doc update: RS485CommClass --- .../RS485_fullduplex/RS485_fullduplex.ino | 2 - .../RS485_halfduplex/RS485_halfduplex.ino | 9 ++-- src/RS485CommClass.cpp | 3 +- src/RS485CommClass.h | 48 +++++++++++++------ 4 files changed, 38 insertions(+), 24 deletions(-) diff --git a/examples/RS485_fullduplex/RS485_fullduplex.ino b/examples/RS485_fullduplex/RS485_fullduplex.ino index 6d1dfcf..eb10ff0 100644 --- a/examples/RS485_fullduplex/RS485_fullduplex.ino +++ b/examples/RS485_fullduplex/RS485_fullduplex.ino @@ -23,7 +23,6 @@ unsigned long counter = 0; void setup() { - Serial.begin(115200); while (!Serial) { ; // wait for serial port to connect. @@ -47,7 +46,6 @@ void setup() // Start in receive mode MachineControl_RS485Comm.receive(); - Serial.println("Initialization done!"); } diff --git a/examples/RS485_halfduplex/RS485_halfduplex.ino b/examples/RS485_halfduplex/RS485_halfduplex.ino index 28517d6..789584c 100644 --- a/examples/RS485_halfduplex/RS485_halfduplex.ino +++ b/examples/RS485_halfduplex/RS485_halfduplex.ino @@ -24,11 +24,10 @@ unsigned long counter { 0 }; void setup() { Serial.begin(115200); - // Wait for Serial or start after 2.5s - for (auto const timeout = millis() + 2500; !Serial && timeout < millis(); delay(500)) - ; - - delay(2500); + while (!Serial) { + ; // wait for serial port to connect. + } + delay(1000); Serial.println("Start RS485 initialization"); // Set the PMC Communication Protocols to default config diff --git a/src/RS485CommClass.cpp b/src/RS485CommClass.cpp index a55872d..098f43e 100644 --- a/src/RS485CommClass.cpp +++ b/src/RS485CommClass.cpp @@ -2,7 +2,6 @@ * @file RS485CommClass.cpp * @author Leonardo Cavagnis * @brief Source file for the RS485CommClass used to initialize and interact with RS485 and RS232 communication protocols on the Portenta Machine Control board. - * */ /* Includes -----------------------------------------------------------------*/ @@ -11,7 +10,7 @@ /* Functions -----------------------------------------------------------------*/ -RS485CommClass::RS485CommClass(arduino::UART uart_itf, PinName rs_tx_pin, PinName rs_de_pin, PinName rs_re_pin) +RS485CommClass::RS485CommClass(arduino::UART& uart_itf, PinName rs_tx_pin, PinName rs_de_pin, PinName rs_re_pin) : RS485Class(uart_itf, PinNameToIndex(rs_tx_pin), PinNameToIndex(rs_de_pin), PinNameToIndex(rs_re_pin)) { } diff --git a/src/RS485CommClass.h b/src/RS485CommClass.h index ef4b80c..f57d665 100644 --- a/src/RS485CommClass.h +++ b/src/RS485CommClass.h @@ -1,9 +1,9 @@ /** - * @file COMMClass.h + * @file RS485CommClass.h * @author Leonardo Cavagnis * @brief Header file for the RS485CommClass used to initialize and interact with RS485 and RS232 communication protocols on the Portenta Machine Control board. * - * This library provides a class to manage the RS485 and RS234 protocols of the Portenta Machine Control board. + * This library provides a class to manage the RS485 and RS232 communication protocols of the Portenta Machine Control board. * It allows initializing and interacting with the serial protocols. The library also initializes the corresponding LEDs. */ @@ -11,54 +11,64 @@ #define __RS485_COMM_CLASS_H /* Includes -------------------------------------------------------------------*/ -#include -#include +#include +#include #include /* Class ----------------------------------------------------------------------*/ /** * @class RS485CommClass - * @brief Class for managing the RS485 and RS232 protocols of the Portenta Machine Control. + * @brief Class for managing the RS485 and RS232 communication protocols of the Portenta Machine Control. + * + * The `RS485CommClass` is a subclass of `RS485Class` and provides methods to work with the RS485 and RS232 communication protocols on the Portenta Machine Control board. + * It includes features to initialize, configure, and interact with the serial protocols. The library also initializes the corresponding LED for RS485. */ - class RS485CommClass : public RS485Class { public: /** * @brief Construct a RS485CommClass object. * - * This constructor initializes a RS485CommClass object. + * This constructor initializes a RS485CommClass object with the specified UART interface and pins. + * + * @param uart_itf The UART interface to use for communication. + * @param rs_tx_pin The pin for transmitting data on the RS485 Bus. + * @param rs_de_pin The pin for enabling the RS485 driver. + * @param rs_re_pin The pin for setting the RS485 driver in receive or transmit mode. */ - RS485CommClass(arduino::UART uart_itf, PinName rs_tx_pin = PA_0, PinName rs_de_pin = PI_13, PinName rs_re_pin = PI_10); + RS485CommClass(arduino::UART& uart_itf, PinName rs_tx_pin = PA_0, PinName rs_de_pin = PI_13, PinName rs_re_pin = PI_10); /** * @brief Destruct the RS485CommClass object. * * This destructor releases any resources used by the RS485CommClass object. + * It will automatically be called when the object goes out of scope. */ ~RS485CommClass(); /** * @brief Begin the RS485 communication protocol. * - * This method initializes the RS485 communication protocols - * - * @todo ////PARAMETERS - * - * @return true If the initialization is successful, false otherwise. + * This method initializes the RS485 communication protocol with the specified baud rate and pre/post delays. + * + * @param baudrate The desired baud rate for the RS485 communication. + * @param predelay The delay before sending data in the RS485 communication (default: RS485_DEFAULT_PRE_DELAY). + * @param postdelay The delay after sending data in the RS485 communication (default: RS485_DEFAULT_POST_DELAY). */ void begin(unsigned long baudrate = 115200, int predelay = RS485_DEFAULT_PRE_DELAY, int postdelay = RS485_DEFAULT_POST_DELAY); /** * @brief Close the RS485 communication protocol. * - * This method de-initializes the RS485 communication protocol + * This method de-initializes the RS485 communication protocol, stopping communication on the RS485 Bus. */ void end(); /** * @brief Set RS485 mode to RS232. * + * This method sets the RS485 mode to RS232 or RS485. + * * @param enable If true, sets the RS485 mode to RS232, else sets to RS485 mode. */ void setModeRS232(bool enable); @@ -66,6 +76,8 @@ class RS485CommClass : public RS485Class { /** * @brief Set YZ termination for RS485 communication. * + * This method enables or disables YZ termination for RS485 communication. + * * @param enable If true, enables YZ termination, else disables it. */ void setYZTerm(bool enable); @@ -73,6 +85,8 @@ class RS485CommClass : public RS485Class { /** * @brief Set AB termination for RS485 communication. * + * This method enables or disables AB termination for RS485 communication. + * * @param enable If true, enables AB termination, else disables it. */ void setABTerm(bool enable); @@ -80,6 +94,8 @@ class RS485CommClass : public RS485Class { /** * @brief Set the slew rate for RS485 communication. * + * This method enables or disables the slew rate control for RS485 communication. + * * @param enable If true, enables the slew rate control, else disables it. */ void setSlew(bool enable); @@ -87,6 +103,8 @@ class RS485CommClass : public RS485Class { /** * @brief Set RS485 communication to Full Duplex mode. * + * This method sets RS485 communication to Full Duplex or Half Duplex mode. + * * @param enable If true, sets RS485 communication to Full Duplex mode, else to Half Duplex mode. */ void setFullDuplex(bool enable); @@ -109,4 +127,4 @@ class RS485CommClass : public RS485Class { extern RS485CommClass MachineControl_RS485Comm; -#endif /* __RS485_COMM_CLASS_H */ \ No newline at end of file +#endif /* __RS485_COMM_CLASS_H */ From dc3631d5e823e16ca8554c87be64ae988c1eada6 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 1 Aug 2023 17:22:28 +0200 Subject: [PATCH 24/47] create two different classes for the temp probes: RTD (RTDTempProbeClass) and TC (TCTempProbeClass) --- examples/Temp_probes_RTD/Temp_probes_RTD.ino | 68 ++++++------ .../Temp_probes_Thermocouples.ino | 14 +-- src/Arduino_MachineControl.h | 3 +- src/CANCommClass.h | 2 +- ...pProbesClass.cpp => RTDTempProbeClass.cpp} | 71 +++++------- src/RTDTempProbeClass.h | 94 ++++++++++++++++ src/TCTempProbeClass.cpp | 102 +++++++++++++++++ src/TCTempProbeClass.h | 90 +++++++++++++++ src/TempProbesClass.h | 103 ------------------ 9 files changed, 356 insertions(+), 191 deletions(-) rename src/{TempProbesClass.cpp => RTDTempProbeClass.cpp} (54%) create mode 100644 src/RTDTempProbeClass.h create mode 100644 src/TCTempProbeClass.cpp create mode 100644 src/TCTempProbeClass.h delete mode 100644 src/TempProbesClass.h diff --git a/examples/Temp_probes_RTD/Temp_probes_RTD.ino b/examples/Temp_probes_RTD/Temp_probes_RTD.ino index cbf132b..ba97b71 100644 --- a/examples/Temp_probes_RTD/Temp_probes_RTD.ino +++ b/examples/Temp_probes_RTD/Temp_probes_RTD.ino @@ -25,120 +25,120 @@ void setup() { Serial.begin(9600); Serial.println("MAX31865 PT100 Sensor Test!"); - MachineControl_TempProbes.begin(TEMPPROBE_RTD, THREE_WIRE); + MachineControl_RTDTempProbe.begin(THREE_WIRE); } void loop() { - MachineControl_TempProbes.selectChannel(0); + MachineControl_RTDTempProbe.selectChannel(0); Serial.println("CHANNEL 0 SELECTED"); - uint16_t rtd = MachineControl_TempProbes.RTD.readRTD(); + uint16_t rtd = MachineControl_RTDTempProbe.readRTD(); float ratio = rtd; ratio /= 32768; // Check and print any faults - uint8_t fault = MachineControl_TempProbes.RTD.readFault(); + uint8_t fault = MachineControl_RTDTempProbe.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { + if (MachineControl_RTDTempProbe.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - MachineControl_TempProbes.RTD.clearFault(); + MachineControl_RTDTempProbe.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_RTDTempProbe.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(100); - MachineControl_TempProbes.selectChannel(1); + MachineControl_RTDTempProbe.selectChannel(1); Serial.println("CHANNEL 1 SELECTED"); - rtd = MachineControl_TempProbes.RTD.readRTD(); + rtd = MachineControl_RTDTempProbe.readRTD(); ratio = rtd; ratio /= 32768; // Check and print any faults - fault = MachineControl_TempProbes.RTD.readFault(); + fault = MachineControl_RTDTempProbe.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { + if (MachineControl_RTDTempProbe.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - MachineControl_TempProbes.RTD.clearFault(); + MachineControl_RTDTempProbe.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_RTDTempProbe.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(100); - MachineControl_TempProbes.selectChannel(2); + MachineControl_RTDTempProbe.selectChannel(2); Serial.println("CHANNEL 2 SELECTED"); - rtd = MachineControl_TempProbes.RTD.readRTD(); + rtd = MachineControl_RTDTempProbe.readRTD(); ratio = rtd; ratio /= 32768; // Check and print any faults - fault = MachineControl_TempProbes.RTD.readFault(); + fault = MachineControl_RTDTempProbe.readFault(); if (fault) { Serial.print("Fault 0x"); Serial.println(fault, HEX); - if (MachineControl_TempProbes.RTD.getHighThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getHighThresholdFault(fault)) { Serial.println("RTD High Threshold"); } - if (MachineControl_TempProbes.RTD.getLowThresholdFault(fault)) { + if (MachineControl_RTDTempProbe.getLowThresholdFault(fault)) { Serial.println("RTD Low Threshold"); } - if (MachineControl_TempProbes.RTD.getLowREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowREFINFault(fault)) { Serial.println("REFIN- > 0.85 x Bias"); } - if (MachineControl_TempProbes.RTD.getHighREFINFault(fault)) { + if (MachineControl_RTDTempProbe.getHighREFINFault(fault)) { Serial.println("REFIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getLowRTDINFault(fault)) { + if (MachineControl_RTDTempProbe.getLowRTDINFault(fault)) { Serial.println("RTDIN- < 0.85 x Bias - FORCE- open"); } - if (MachineControl_TempProbes.RTD.getVoltageFault(fault)) { + if (MachineControl_RTDTempProbe.getVoltageFault(fault)) { Serial.println("Under/Over voltage"); } - MachineControl_TempProbes.RTD.clearFault(); + MachineControl_RTDTempProbe.clearFault(); } else { Serial.print("RTD value: "); Serial.println(rtd); Serial.print("Ratio = "); Serial.println(ratio, 8); Serial.print("Resistance = "); Serial.println(RREF * ratio, 8); - Serial.print("Temperature = "); Serial.println(MachineControl_TempProbes.RTD.readTemperature(RNOMINAL, RREF)); + Serial.print("Temperature = "); Serial.println(MachineControl_RTDTempProbe.readTemperature(RNOMINAL, RREF)); } Serial.println(); delay(1000); diff --git a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino index 51e999b..9e1ab4a 100644 --- a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino +++ b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino @@ -21,31 +21,31 @@ void setup() { Serial.begin(9600); // Initialize temperature probes - MachineControl_TempProbes.begin(TEMPPROBE_TC); + MachineControl_TCTempProbe.begin(); Serial.println("Temperature probes initialization done"); } void loop() { //Set CH0, has internal 150 ms delay - MachineControl_TempProbes.selectChannel(0); + MachineControl_TCTempProbe.selectChannel(0); //Take CH0 measurement - float temp_ch0 = MachineControl_TempProbes.TC.readTemperature(); + float temp_ch0 = MachineControl_TCTempProbe.readTemperature(); Serial.print("Temperature CH0 [°C]: "); Serial.print(temp_ch0); Serial.println(); //Set CH1, has internal 150 ms delay - MachineControl_TempProbes.selectChannel(1); + MachineControl_TCTempProbe.selectChannel(1); //Take CH1 measurement - float temp_ch1 = MachineControl_TempProbes.TC.readTemperature(); + float temp_ch1 = MachineControl_TCTempProbe.readTemperature(); Serial.print("Temperature CH1 [°C]: "); Serial.print(temp_ch1); Serial.println(); //Set CH2, has internal 150 ms delay - MachineControl_TempProbes.selectChannel(2); + MachineControl_TCTempProbe.selectChannel(2); //Take CH2 measurement - float temp_ch2 = MachineControl_TempProbes.TC.readTemperature(); + float temp_ch2 = MachineControl_TCTempProbe.readTemperature(); Serial.print("Temperature CH2 [°C]: "); Serial.print(temp_ch2); Serial.println(); diff --git a/src/Arduino_MachineControl.h b/src/Arduino_MachineControl.h index 909f6e7..d13bd17 100644 --- a/src/Arduino_MachineControl.h +++ b/src/Arduino_MachineControl.h @@ -6,7 +6,8 @@ #include "DigitalOutputsClass.h" #include "ProgrammableDIOClass.h" #include "ProgrammableDINClass.h" -#include "TempProbesClass.h" +#include "RTDTempProbeClass.h" +#include "TCTempProbeClass.h" #include "RtcControllerClass.h" #include "USBClass.h" #include "EncoderClass.h" diff --git a/src/CANCommClass.h b/src/CANCommClass.h index 3d428d0..ce9d156 100644 --- a/src/CANCommClass.h +++ b/src/CANCommClass.h @@ -24,7 +24,7 @@ * The `CANCommClass` is a subclass of `mbed::CAN` and provides methods to work with the CAN Bus communication protocol on the Portenta Machine Control board. * It includes initialization of the corresponding LED for CAN. */ -class CANCommClass: public mbed::CAN { +class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use Arduino_CAN public: /** * @brief Construct a CANCommClass object. diff --git a/src/TempProbesClass.cpp b/src/RTDTempProbeClass.cpp similarity index 54% rename from src/TempProbesClass.cpp rename to src/RTDTempProbeClass.cpp index d959df6..a64a910 100644 --- a/src/TempProbesClass.cpp +++ b/src/RTDTempProbeClass.cpp @@ -1,11 +1,11 @@ /** - * @file TempProbesClass.cpp + * @file RTDTempProbeClass.cpp * @author Leonardo Cavagnis - * @brief Source file for the Temperature Probes connector of the Portenta Machine Control. + * @brief Source file for the Resistance Temperature Detector (RTD) temperature sensor connector of the Portenta Machine Control. */ /* Includes -----------------------------------------------------------------*/ -#include "TempProbesClass.h" +#include "RTDTempProbeClass.h" #if __has_include("portenta_info.h") #include "portenta_info.h" @@ -15,45 +15,33 @@ uint8_t* boardInfo(); #endif /* Functions -----------------------------------------------------------------*/ -TempProbesClass::TempProbesClass(PinName ch_sel0_pin, - PinName ch_sel1_pin, - PinName ch_sel2_pin, - PinName rtd_th_pin) -: _ch_sel0{ch_sel0_pin}, _ch_sel1{ch_sel0_pin}, _ch_sel2{ch_sel2_pin}, _rtd_th{rtd_th_pin} +RTDTempProbeClass::RTDTempProbeClass(PinName rtd_cs_pin, + PinName ch_sel0_pin, + PinName ch_sel1_pin, + PinName ch_sel2_pin, + PinName rtd_th_pin) +: MAX31865Class(rtd_cs_pin), _rtd_cs{rtd_cs_pin}, _ch_sel0{ch_sel0_pin}, _ch_sel1{ch_sel0_pin}, _ch_sel2{ch_sel2_pin}, _rtd_th{rtd_th_pin} { } -TempProbesClass::~TempProbesClass() +RTDTempProbeClass::~RTDTempProbeClass() { } -bool TempProbesClass::begin(uint8_t tempprobe_type, uint8_t io_address) { - bool status = true; - - switch(tempprobe_type) { - case TEMPPROBE_RTD: - TempProbesClass::RTD.begin(io_address); - _enableRTD(); - break; - case TEMPPROBE_TC: - TempProbesClass::TC.begin(); - _enableTC(); - break; - default: - status = false; - break; - } +bool RTDTempProbeClass::begin(uint8_t io_address) { + MAX31865Class::begin(io_address); pinMode(_ch_sel0, OUTPUT); pinMode(_ch_sel1, OUTPUT); pinMode(_ch_sel2, OUTPUT); pinMode(_rtd_th, OUTPUT); - pinMode(PI_0, OUTPUT); - pinMode(PA_6, OUTPUT); + pinMode(_rtd_cs, OUTPUT); + + _enable(); - return status; + return true; } -void TempProbesClass::selectChannel(int channel) { +void RTDTempProbeClass::selectChannel(int channel) { #ifdef TRY_REV2_RECOGNITION // check if OTP data is present AND the board is mounted on a r2 carrier @@ -98,28 +86,21 @@ void TempProbesClass::selectChannel(int channel) { delay(150); } -void TempProbesClass::end() { - _disableCS(); -} - -void TempProbesClass::_enableTC() { - digitalWrite(_rtd_th, LOW); - - digitalWrite(PI_0, LOW); - digitalWrite(PA_6, HIGH); +void RTDTempProbeClass::end() { + MAX31865Class::end(); + + _disable(); } -void TempProbesClass::_enableRTD() { +void RTDTempProbeClass::_enable() { digitalWrite(_rtd_th, HIGH); - digitalWrite(PI_0, HIGH); - digitalWrite(PA_6, LOW); + digitalWrite(_rtd_cs, LOW); } -void TempProbesClass::_disableCS() { - digitalWrite(PI_0, HIGH); - digitalWrite(PA_6, HIGH); +void RTDTempProbeClass::_disable() { + digitalWrite(_rtd_cs, HIGH); } -TempProbesClass MachineControl_TempProbes; +RTDTempProbeClass MachineControl_RTDTempProbe; /**** END OF FILE ****/ \ No newline at end of file diff --git a/src/RTDTempProbeClass.h b/src/RTDTempProbeClass.h new file mode 100644 index 0000000..1dc94a3 --- /dev/null +++ b/src/RTDTempProbeClass.h @@ -0,0 +1,94 @@ +/** + * @file RTDTempProbeClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Resistance Temperature Detector (RTD) temperature sensor connector of the Portenta Machine Control. + * + * This library allows interfacing with RTD temperature sensors using the MAX31865 digital converter. + * It provides methods to select input channel, enabling and disabling the sensor, and reading temperature values. + */ + +#ifndef __RTD_TEMPPROBE_CLASS_H +#define __RTD_TEMPPROBE_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include "utility/MAX31865/MAX31865.h" +#include "utility/THERMOCOUPLE/MAX31855.h" +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class RTDTempProbeClass + * @brief Class for managing RTD temperature sensor inputs of the Portenta Machine Control. + * + * This class allows interfacing with RTD temperature sensors through the use of the MAX31865 digital converter. + * It provides methods to configure and read temperature values from the selected input channel. + */ +class RTDTempProbeClass: public MAX31865Class { +public: + /** + * @brief Construct a RTDTempProbeClass object. + * + * This constructor initializes a RTDTempProbeClass object with the specified pin assignments for channel selection and RTD connection. + * + * @param rtd_cs_pin The pin number for the chip select (CS) pin of the RTD temperature sensor. + * @param ch_sel0_pin The pin number for the first channel selection bit. + * @param ch_sel1_pin The pin number for the second channel selection bit. + * @param ch_sel2_pin The pin number for the third channel selection bit. + * @param rtd_th_pin The pin number for the RTD connection. + */ + RTDTempProbeClass(PinName rtd_cs_pin = PA_6, + PinName ch_sel0_pin = PD_6, + PinName ch_sel1_pin = PI_4, + PinName ch_sel2_pin = PG_10, + PinName rtd_th_pin = PC_15); + + /** + * @brief Destruct the RTDTempProbeClass object. + * + * This destructor releases any resources used by the RTDTempProbeClass object. + */ + ~RTDTempProbeClass(); + + /** + * @brief Initialize the RTDTempProbeClass with the specified I/O address. + * + * @param io_address The I/O address for communication with the digital converters (default is THREE_WIRE). + * @return true If initialization is successful, false otherwise. + */ + bool begin(uint8_t io_address = THREE_WIRE); + + /** + * @brief Disable the temperature sensors and release any resources. + */ + void end(); + + /** + * @brief Select the input channel to be read (3 channels available). + * + * @param channel The channel number (0-2) to be selected for temperature reading. + */ + void selectChannel(int channel); + +private: + PinName _rtd_cs; // Pin for the CS of RTD + PinName _ch_sel0; // Pin for the first channel selection bit + PinName _ch_sel1; // Pin for the second channel selection bit + PinName _ch_sel2; // Pin for the third channel selection bit + PinName _rtd_th; // Pin for the RTD connection + + /** + * @brief Enable the chip select (CS) of the MAX31865 digital converter. + */ + void _enable(); + + /** + * @brief Disable the chip select (CS) of the MAX31865 digital converter. + */ + void _disable(); +}; + +extern RTDTempProbeClass MachineControl_RTDTempProbe; + +#endif /* __RTD_TEMPPROBE_CLASS_H */ diff --git a/src/TCTempProbeClass.cpp b/src/TCTempProbeClass.cpp new file mode 100644 index 0000000..9bf5138 --- /dev/null +++ b/src/TCTempProbeClass.cpp @@ -0,0 +1,102 @@ +/** + * @file TCTempProbeClass.cpp + * @author Leonardo Cavagnis + * @brief Source file for the Thermocouple (TC) temperature sensor connector of the Portenta Machine Control. + */ + +/* Includes -----------------------------------------------------------------*/ +#include "TCTempProbeClass.h" + +#if __has_include("portenta_info.h") +#include "portenta_info.h" +#define TRY_REV2_RECOGNITION +uint8_t* boardInfo(); +#define PMC_R2_SKU (24 << 8 | 3) +#endif + +/* Functions -----------------------------------------------------------------*/ +TCTempProbeClass::TCTempProbeClass(PinName tc_cs_pin, + PinName ch_sel0_pin, + PinName ch_sel1_pin, + PinName ch_sel2_pin) +: MAX31855Class(tc_cs_pin), _tc_cs{tc_cs_pin}, _ch_sel0{ch_sel0_pin}, _ch_sel1{ch_sel0_pin}, _ch_sel2{ch_sel2_pin} +{ } + +TCTempProbeClass::~TCTempProbeClass() +{ } + +bool TCTempProbeClass::begin() { + MAX31855Class::begin(); + + pinMode(_ch_sel0, OUTPUT); + pinMode(_ch_sel1, OUTPUT); + pinMode(_ch_sel2, OUTPUT); + + pinMode(_tc_cs, OUTPUT); + + _enable(); + + return true; +} + +void TCTempProbeClass::selectChannel(int channel) { + +#ifdef TRY_REV2_RECOGNITION + // check if OTP data is present AND the board is mounted on a r2 carrier + auto info = (PortentaBoardInfo*)boardInfo(); + if (info->magic == 0xB5 && info->carrier == PMC_R2_SKU) { + // reverse channels 0 and 2 + switch (channel) { + case 0: + channel = 2; + break; + case 2: + channel = 0; + break; + default: + break; + } + } +#endif +#undef TRY_REV2_RECOGNITION + switch(channel) { + case 0: + digitalWrite(_ch_sel0, HIGH); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, LOW); + break; + case 1: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, HIGH); + digitalWrite(_ch_sel2, LOW); + break; + case 2: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, HIGH); + break; + default: + digitalWrite(_ch_sel0, LOW); + digitalWrite(_ch_sel1, LOW); + digitalWrite(_ch_sel2, LOW); + break; + } + delay(150); +} + +void TCTempProbeClass::end() { + MAX31855Class::end(); + + _disable(); +} + +void TCTempProbeClass::_enable() { + digitalWrite(_tc_cs, LOW); +} + +void TCTempProbeClass::_disable() { + digitalWrite(_tc_cs, HIGH); +} + +TCTempProbeClass MachineControl_TCTempProbe; +/**** END OF FILE ****/ \ No newline at end of file diff --git a/src/TCTempProbeClass.h b/src/TCTempProbeClass.h new file mode 100644 index 0000000..c111d68 --- /dev/null +++ b/src/TCTempProbeClass.h @@ -0,0 +1,90 @@ +/** + * @file TCTempProbeClass.h + * @author Leonardo Cavagnis + * @brief Header file for the Thermocouple (TC) temperature sensor connector of the Portenta Machine Control. + * + * This library allows interfacing with TC temperature sensors using the MAX31855 digital converter. + * It provides methods to select input channel, enabling and disabling the sensor, and reading temperature values. + */ + +#ifndef __TC_TEMPPROBE_CLASS_H +#define __TC_TEMPPROBE_CLASS_H + +/* Includes -------------------------------------------------------------------*/ +#include "utility/MAX31865/MAX31865.h" +#include "utility/THERMOCOUPLE/MAX31855.h" +#include +#include + +/* Class ----------------------------------------------------------------------*/ + +/** + * @class TCTempProbeClass + * @brief Class for managing thermocouples temperature sensor of the Portenta Machine Control. + * + * This class allows interfacing with thermocouple temperature sensors through the use of the MAX31855 digital converter. + * It provides methods to configure and read temperature values from the selected input channel. + */ +class TCTempProbeClass: public MAX31855Class { +public: + /** + * @brief Construct a TCTempProbeClass object. + * + * This constructor initializes a TCTempProbeClass object with the specified pin assignments for channel selection and TC connection. + * + * @param tc_cs_pin The pin number for the chip select (CS) pin of the Thermocouple temperature sensor. + * @param ch_sel0_pin The pin number for the first channel selection bit. + * @param ch_sel1_pin The pin number for the second channel selection bit. + * @param ch_sel2_pin The pin number for the third channel selection bit. + */ + TCTempProbeClass(PinName tc_cs_pin = PI_0, + PinName ch_sel0_pin = PD_6, + PinName ch_sel1_pin = PI_4, + PinName ch_sel2_pin = PG_10); + + /** + * @brief Destruct the TCTempProbeClass object. + * + * This destructor releases any resources used by the TCTempProbeClass object. + */ + ~TCTempProbeClass(); + + /** + * @brief Initialize the TCTempProbeClass. + * + * @return true If initialization is successful, false otherwise. + */ + bool begin(); + + /** + * @brief Disable the temperature sensors and release any resources. + */ + void end(); + + /** + * @brief Select the input channel to be read (3 channels available). + * + * @param channel The channel number (0-2) to be selected for temperature reading. + */ + void selectChannel(int channel); + +private: + PinName _tc_cs; // Pin for the CS of Thermocouple + PinName _ch_sel0; // Pin for the first channel selection bit + PinName _ch_sel1; // Pin for the second channel selection bit + PinName _ch_sel2; // Pin for the third channel selection bit + + /** + * @brief Enable the chip select (CS) of the MAX31855 digital converter. + */ + void _enable(); + + /** + * @brief Disable the chip select (CS) of the MAX31855 digital converter. + */ + void _disable(); +}; + +extern TCTempProbeClass MachineControl_TCTempProbe; + +#endif /* __TC_TEMPPROBE_CLASS_H */ diff --git a/src/TempProbesClass.h b/src/TempProbesClass.h deleted file mode 100644 index 238f417..0000000 --- a/src/TempProbesClass.h +++ /dev/null @@ -1,103 +0,0 @@ -/** - * @file TempProbesClass.h - * @author Leonardo Cavagnis - * @brief Header file for the Temperature Probes connector of the Portenta Machine Control. - * - * This library allows interfacing with RTD (Resistance Temperature Detector) and Thermocouple temperature sensors - * using the MAX31865 and MAX31855 digital converters. It provides methods to select the sensor type and input channel, - * enabling and disabling the temperature sensors, and reading temperature values. - */ - -#ifndef __TEMPPROBES_CLASS_H -#define __TEMPPROBES_CLASS_H - -/* Includes -------------------------------------------------------------------*/ -#include "utility/MAX31865/MAX31865.h" -#include "utility/THERMOCOUPLE/MAX31855.h" -#include -#include - -/* Constants ------------------------------------------------------------------*/ -#define TEMPPROBE_RTD 1 -#define TEMPPROBE_TC 2 - -/* Class ----------------------------------------------------------------------*/ - -/** - * @class TempProbesClass - * @brief Class for managing temperature sensor inputs (RTD and thermocouples) of the Portenta Machine Control. - * - * This class allows interfacing with RTD and thermocouple temperature sensors through the use of the MAX31865 and MAX31855 digital converters. - * It provides methods to configure and read temperature values from the selected input channel. - */ -class TempProbesClass { -public: - /** - * @brief Construct a TempProbesClass object. - * - * This constructor initializes a TempProbesClass object with the specified pin assignments for channel selection and RTD connection. - * - * @param ch_sel0_pin The pin number for the first channel selection bit. - * @param ch_sel1_pin The pin number for the second channel selection bit. - * @param ch_sel2_pin The pin number for the third channel selection bit. - * @param rtd_th_pin The pin number for the RTD connection. - */ - TempProbesClass(PinName ch_sel0_pin = PD_6, PinName ch_sel1_pin = PI_4, PinName ch_sel2_pin = PG_10, PinName rtd_th_pin = PC_15); - - /** - * @brief Destruct the TempProbesClass object. - * - * This destructor releases any resources used by the TempProbesClass object. - */ - ~TempProbesClass(); - - /** - * @brief Initialize the TempProbesClass with the specified temperature probe type and I/O address. - * - * @param tempprobe_type The type of temperature probe (RTD or thermocouple). - * @param io_address The I/O address for communication with the digital converters (default is THREE_WIRE). - * @return true If initialization is successful, false otherwise. - */ - bool begin(uint8_t tempprobe_type, uint8_t io_address = THREE_WIRE); - - /** - * @brief Select the input channel to be read (3 channels available). - * - * @param channel The channel number (0-2) to be selected for temperature reading. - */ - void selectChannel(int channel); - - /** - * @brief Disable the temperature sensors and release any resources. - */ - void end(); - - // Instances of the MAX31865 and MAX31855 digital converter classes for RTD and thermocouple respectively - MAX31865Class RTD = MAX31865Class(PA_6); - MAX31855Class TC = MAX31855Class(7); - -private: - PinName _ch_sel0; // Pin for the first channel selection bit - PinName _ch_sel1; // Pin for the second channel selection bit - PinName _ch_sel2; // Pin for the third channel selection bit - PinName _rtd_th; // Pin for the RTD connection - - /** - * @brief Enable the chip select (CS) of the Thermocouple to digital converter and disable the CS for the RTD to digital converter. - */ - void _enableTC(); - - /** - * @brief Enable the chip select (CS) of the RTD to digital converter and disable the CS of the Thermocouple to digital converter. - */ - void _enableRTD(); - - /** - * @brief Disable chip select (CS) for both RTD and thermocouple digital converters. - */ - void _disableCS(); -}; - -extern TempProbesClass MachineControl_TempProbes; - -#endif /* __TEMPPROBES_CLASS_H */ From 407b907bf9364f8afbfe9f6c1037d33cc90ac63f Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 2 Aug 2023 15:58:22 +0200 Subject: [PATCH 25/47] Encoder: remove operator [] to access encoder channel --- examples/Encoders/Encoders.ino | 12 +++---- src/EncoderClass.cpp | 48 ++++++++++++++++++++++---- src/EncoderClass.h | 63 ++++++++++++++++++++++++++-------- 3 files changed, 96 insertions(+), 27 deletions(-) diff --git a/examples/Encoders/Encoders.ino b/examples/Encoders/Encoders.ino index 8fb5960..d843df6 100644 --- a/examples/Encoders/Encoders.ino +++ b/examples/Encoders/Encoders.ino @@ -8,19 +8,19 @@ void setup() { void loop() { // put your main code here, to run repeatedly: Serial.print("Encoder 0 State: "); - Serial.println(MachineControl_Encoders[0].getCurrentState(),BIN); + Serial.println(MachineControl_Encoders.getCurrentState(0),BIN); Serial.print("Encoder 0 Pulses: "); - Serial.println(MachineControl_Encoders[0].getPulses()); + Serial.println(MachineControl_Encoders.getPulses(0)); Serial.print("Encoder 0 Revolutions: "); - Serial.println(MachineControl_Encoders[0].getRevolutions()); + Serial.println(MachineControl_Encoders.getRevolutions(0)); Serial.println(); Serial.print("Encoder 1 State: "); - Serial.println(MachineControl_Encoders[1].getCurrentState(),BIN); + Serial.println(MachineControl_Encoders.getCurrentState(1),BIN); Serial.print("Encoder 1 Pulses: "); - Serial.println(MachineControl_Encoders[1].getPulses()); + Serial.println(MachineControl_Encoders.getPulses(1)); Serial.print("Encoder 1 Revolutions: "); - Serial.println(MachineControl_Encoders[1].getRevolutions()); + Serial.println(MachineControl_Encoders.getRevolutions(1)); Serial.println(); delay(25); } diff --git a/src/EncoderClass.cpp b/src/EncoderClass.cpp index 50bdaf8..3fe546f 100644 --- a/src/EncoderClass.cpp +++ b/src/EncoderClass.cpp @@ -1,7 +1,7 @@ /** * @file EncoderClass.cpp * @author Leonardo Cavagnis - * @brief Source file for the EncoderClass of the Portenta Machine Control. + * @brief Source file for the encoder module of the Portenta Machine Control. */ /* Includes -----------------------------------------------------------------*/ @@ -17,15 +17,49 @@ EncoderClass::EncoderClass(PinName enc0_A_pin, PinName enc0_B_pin, PinName enc0_ EncoderClass::~EncoderClass() { } -QEI& EncoderClass::operator[](int index) { - switch (index) { +void EncoderClass::reset(int channel) { + switch (channel) { case 0: - return _enc0; + _enc0.reset(); + break; case 1: - return _enc1; + _enc1.reset(); + break; default: - // Return encoder 0 by default if an invalid index is provided - return _enc0; + return; + } +} + +int EncoderClass::getCurrentState(int channel) { + switch (channel) { + case 0: + return _enc0.getCurrentState(); + case 1: + return _enc1.getCurrentState(); + default: + return -1; + } +} + +int EncoderClass::getPulses(int channel) { + switch (channel) { + case 0: + return _enc0.getPulses(); + case 1: + return _enc1.getPulses(); + default: + return -1; + } +} + +int EncoderClass::getRevolutions(int channel) { + switch (channel) { + case 0: + return _enc0.getRevolutions(); + case 1: + return _enc1.getRevolutions(); + default: + return -1; } } diff --git a/src/EncoderClass.h b/src/EncoderClass.h index a8e174f..271d82b 100644 --- a/src/EncoderClass.h +++ b/src/EncoderClass.h @@ -1,7 +1,7 @@ /** * @file EncoderClass.h * @author Leonardo Cavagnis - * @brief Header file for the EncoderClass of the Portenta Machine Control. + * @brief Header file for the encoder module of the Portenta Machine Control. * * This library provides a class to manage the Quadrature Encoder Interface devices * of the Portenta Machine Control. It allows interfacing with two encoders through @@ -22,6 +22,10 @@ /** * @class EncoderClass * @brief Class for managing Quadrature Encoder Interface devices of the Portenta Machine Control. + * + * This class provides methods to interact with two quadrature encoders. Each encoder + * has two channels (A and B) for quadrature signals and an index channel. The class + * allows reading the current state, pulses, and revolutions of each encoder. */ class EncoderClass { public: @@ -31,12 +35,12 @@ class EncoderClass { * This constructor initializes the two QEI objects for encoder 0 and encoder 1 * with the specified pin assignments. * - * @param enc0_A_pin Pin assignment for encoder 0 channel A (default: PA_0). - * @param enc0_B_pin Pin assignment for encoder 0 channel B (default: PB_0). - * @param enc0_I_pin Pin assignment for encoder 0 Index channel (default: PC_0). - * @param enc1_A_pin Pin assignment for encoder 1 channel A (default: PD_0). - * @param enc1_B_pin Pin assignment for encoder 1 channel B (default: PE_0). - * @param enc1_I_pin Pin assignment for encoder 1 Index channel (default: PF_0). + * @param enc0_A_pin Pin assignment for encoder 0 channel A (default: PJ_8). + * @param enc0_B_pin Pin assignment for encoder 0 channel B (default: PH_12). + * @param enc0_I_pin Pin assignment for encoder 0 Index channel (default: PH_11). + * @param enc1_A_pin Pin assignment for encoder 1 channel A (default: PC_13). + * @param enc1_B_pin Pin assignment for encoder 1 channel B (default: PI_7). + * @param enc1_I_pin Pin assignment for encoder 1 Index channel (default: PJ_10). */ EncoderClass(PinName enc0_A_pin = PJ_8, PinName enc0_B_pin = PH_12, PinName enc0_I_pin = PH_11, PinName enc1_A_pin = PC_13, PinName enc1_B_pin = PI_7, PinName enc1_I_pin = PJ_10); @@ -49,14 +53,45 @@ class EncoderClass { ~EncoderClass(); /** - * @brief Get the QEI object for the specified encoder index. - * - * This method returns a reference to the QEI object for the specified encoder index. - * - * @param index The index for selecting the encoder (0 or 1). - * @return A reference to the corresponding QEI object. + * @brief Reset the encoder counter for the specified channel. + * + * @param channel The encoder channel (0 or 1) to reset. + */ + void reset(int channel); + + /** + * @brief Get the current state of the specified encoder channel. + * + * The current state is the value of the encoder counter. + * + * @param channel The encoder channel (0 or 1) to read the state from. + * @return The current state of the encoder channel as a 2-bit number, where: + * bit 0 = The reading from channel B + * bit 1 = The reading from channel A + */ + int getCurrentState(int channel); + + /** + * @brief Get the number of pulses counted by the specified encoder channel. + * + * This method returns the number of pulses counted by the encoder. Each pulse + * corresponds to a change in the encoder's quadrature signal. + * + * @param channel The encoder channel (0 or 1) to read the pulses from. + * @return The number of pulses counted by the encoder channel. + */ + int getPulses(int channel); + + /** + * @brief Get the number of revolutions counted by the specified encoder channel. + * + * This method returns the number of full revolutions counted by the encoder. + * It utilizes the index channel to track revolutions. + * + * @param channel The encoder channel (0 or 1) to read the revolutions from. + * @return The number of revolutions counted by the encoder channel. */ - QEI& operator[](int index); + int getRevolutions(int channel); private: QEI _enc0; // QEI object for encoder 0 From 50463b869a5d63df0cb87176410630f372dbb828 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 3 Aug 2023 12:50:23 +0200 Subject: [PATCH 26/47] refactoring Ethernet example using Arduino Ethernet library --- examples/Ethernet/Ethernet.ino | 145 +++++++++++++++++---------------- 1 file changed, 77 insertions(+), 68 deletions(-) diff --git a/examples/Ethernet/Ethernet.ino b/examples/Ethernet/Ethernet.ino index dffd867..e1c8438 100644 --- a/examples/Ethernet/Ethernet.ino +++ b/examples/Ethernet/Ethernet.ino @@ -1,84 +1,93 @@ -#include "EthernetInterface.h" -EthernetInterface net; +#include +#include +#include + +EthernetClient client; +char server[] = "www.ifconfig.io"; // name address (using DNS) + +unsigned long beginMicros, endMicros; +unsigned long byteCount = 0; +bool printWebData = true; // set to false for better speed measurement void setup() { - Serial.begin(115200); - while (!Serial) + Serial.begin(9600); + while (!Serial) { ; + } Serial.println("Ethernet example for H7 + PMC"); - // Bring up the ethernet interface - net.connect(); - - // Show the network address - SocketAddress addr; - net.get_ip_address(&addr); - Serial.print("IP address: "); - Serial.println(addr.get_ip_address() ? addr.get_ip_address() : "None"); - - // Open a socket on the network interface, and create a TCP connection to mbed.org - TCPSocket socket; - socket.open(&net); - - net.gethostbyname("ifconfig.io", &addr); - addr.set_port(80); - socket.connect(addr); - - String request; - request += "GET / HTTP/1.1\r\n"; - request += "Host: ifconfig.io\r\n"; - request += "User-Agent: curl/7.64.1\r\n"; - request += "Accept: */*\r\n"; - request += "Connection: close\r\n"; - request += "\r\n"; - - auto scount = socket.send(request.c_str(), request.length()); - Serial.print("Sent "); - Serial.print(scount); - Serial.println(" bytes: "); - Serial.print(request); - - // Receive a simple HTTP response - const size_t rlen { 64 }; - char rbuffer[rlen + 1] {}; - size_t rcount; - size_t rec { 0 }; - String response; - - while ((rec = socket.recv(rbuffer, rlen)) > 0) { - rcount += rec; - response += rbuffer; - memset(rbuffer, 0, rlen); - } - Serial.print("Received "); - Serial.print(rcount); - Serial.println(" bytes: "); - Serial.println(response); - - const String clTag = "Content-Length: "; - auto clIndex = response.indexOf(clTag); - clIndex += clTag.length(); - auto cl = response.substring(clIndex, clIndex + 2); - const String bodyTag = "\r\n\r\n"; - auto bodyIndex = response.indexOf(bodyTag); - if (bodyIndex != -1) { - bodyIndex += bodyTag.length(); - auto body = response.substring(bodyIndex, bodyIndex + cl.toInt()); - Serial.print("My public IPv4 Address is: "); - Serial.println(body); + if (Ethernet.begin() == 0) { + Serial.println("Failed to configure Ethernet using DHCP"); + while(1); + } else { + Serial.print("DHCP assigned IP "); + Serial.println(Ethernet.localIP()); } + // give the Ethernet shield a second to initialize: + delay(1000); + Serial.print("connecting to "); + Serial.print(server); + Serial.println("..."); - // Close the socket to return its memory and bring down the network interface - socket.close(); + // if you get a connection, report back via serial: + if (client.connect(server, 80)) { + Serial.print("connected to "); + Serial.println(client.remoteIP()); + + // Make a HTTP request: + client.println("GET / HTTP/1.1"); + client.println("Host: ifconfig.io"); + client.println("User-Agent: curl/7.64.1"); + client.println("Connection: close"); + client.println("Accept: */*"); + client.println(); + } else { + // if you didn't get a connection to the server: + Serial.println("connection failed"); + } - // Bring down the ethernet interface - net.disconnect(); - Serial.println("Done"); + beginMicros = micros(); } void loop() { + // if there are incoming bytes available + // from the server, read them and print them: + int len = client.available(); + if (len > 0) { + byte buffer[80]; + if (len > 80) + len = 80; + client.read(buffer, len); + if (printWebData) { + Serial.write(buffer, len); // show in the serial monitor (slows some boards) + } + byteCount = byteCount + len; + } + + // if the server's disconnected, stop the client: + if (!client.connected()) { + endMicros = micros(); + Serial.println(); + Serial.println("disconnecting."); + client.stop(); + Serial.print("Received "); + Serial.print(byteCount); + Serial.print(" bytes in "); + float seconds = (float)(endMicros - beginMicros) / 1000000.0; + Serial.print(seconds, 4); + float rate = (float)byteCount / seconds / 1000.0; + Serial.print(", rate = "); + Serial.print(rate); + Serial.print(" kbytes/second"); + Serial.println(); + + // do nothing forevermore: + while (true) { + delay(1); + } + } } From c091f4a8722777d0511a3e4b0e222755fd9bd18c Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 4 Aug 2023 11:46:31 +0200 Subject: [PATCH 27/47] reimplement CANCommClass using Arduino_CAN library --- examples/CAN/ReadCan/ReadCan.ino | 36 +++++++------------ examples/CAN/WriteCan/WriteCan.ino | 55 +++++++++++++++++------------- src/CANCommClass.cpp | 30 +++++++++++----- src/CANCommClass.h | 48 ++++++++++++++++++++++---- 4 files changed, 107 insertions(+), 62 deletions(-) diff --git a/examples/CAN/ReadCan/ReadCan.ino b/examples/CAN/ReadCan/ReadCan.ino index e34eb26..44c4bdb 100644 --- a/examples/CAN/ReadCan/ReadCan.ino +++ b/examples/CAN/ReadCan/ReadCan.ino @@ -11,35 +11,25 @@ */ #include -#define DATARATE_2MB 2000000 -#define DATARATE_1_5MB 1500000 -#define DATARATE_1MB 1000000 -#define DATARATE_800KB 800000 - -void setup() { +void setup() +{ Serial.begin(9600); while (!Serial) { ; // wait for serial port to connect. } - Serial.println("Start CAN initialization"); - MachineControl_CANComm.begin(DATARATE_800KB); - - Serial.println("Initialization done"); + if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) + { + Serial.println("CAN init failed."); + for (;;) {} + } } -void loop() { - mbed::CANMessage msg; - if (MachineControl_CANComm.read(msg)) { - - // Print the sender ID - Serial.print("ID: "); - Serial.println(msg.id); - - // Print the first Payload Byte - Serial.print("Message received:"); - Serial.println(msg.data[0], DEC); +void loop() +{ + if (MachineControl_CANComm.available()) + { + CanMsg const msg = MachineControl_CANComm.read(); + Serial.println(msg); } - - delay(100); } diff --git a/examples/CAN/WriteCan/WriteCan.ino b/examples/CAN/WriteCan/WriteCan.ino index f5d0ab3..e6ea617 100644 --- a/examples/CAN/WriteCan/WriteCan.ino +++ b/examples/CAN/WriteCan/WriteCan.ino @@ -11,37 +11,46 @@ */ #include -#define DATARATE_2MB 2000000 -#define DATARATE_1_5MB 1500000 -#define DATARATE_1MB 1000000 -#define DATARATE_800KB 800000 +static uint32_t const CAN_ID = 13ul; -void setup() { +void setup() +{ Serial.begin(9600); while (!Serial) { ; // wait for serial port to connect. } - Serial.println("Start CAN initialization"); - - MachineControl_CANComm.begin(DATARATE_800KB); - Serial.println("Initialization done"); + if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) + { + Serial.println("CAN init failed."); + for (;;) {} + } } -int counter = 0; -unsigned char payload = 0x49; -int payload_size = 1; +static uint32_t msg_cnt = 0; + +void loop() +{ + /* Assemble a CAN message */ + uint8_t const msg_data[] = {0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08}; + memcpy((void *)(msg_data + 8), &msg_cnt, sizeof(msg_cnt)); + CanMsg msg(CAN_ID, sizeof(msg_data), msg_data); + + /* Transmit the CAN message, capture and display an + * error core in case of failure. + */ + if (int const rc = MachineControl_CANComm.write(msg); rc <= 0) + { + Serial.print ("CAN write failed with error code "); + Serial.println(rc); + for (;;) { } + } -void loop() { + Serial.println("CAN write message!"); - mbed::CANMessage msg = mbed::CANMessage(13ul, &payload, payload_size); - if (MachineControl_CANComm.write(msg)) { - Serial.println("Message sent"); - } else { - Serial.println("Transmission Error: "); - Serial.println(MachineControl_CANComm.tderror()); - MachineControl_CANComm.reset(); - } + /* Increase the message counter. */ + msg_cnt++; - delay(100); -} + /* Only send one message per second. */ + delay(1000); +} \ No newline at end of file diff --git a/src/CANCommClass.cpp b/src/CANCommClass.cpp index 1c94c33..f179e77 100644 --- a/src/CANCommClass.cpp +++ b/src/CANCommClass.cpp @@ -8,33 +8,45 @@ #include "CANCommClass.h" /* Functions -----------------------------------------------------------------*/ -CANCommClass::CANCommClass(PinName can_tx_pin, PinName can_rx_pin) : - mbed::CAN(can_tx_pin, can_rx_pin) +CANCommClass::CANCommClass(PinName can_tx_pin, PinName can_rx_pin, PinName can_stb_pin) : + _can(can_rx_pin, can_tx_pin), _tx{can_tx_pin}, _rx{can_rx_pin}, _stb{can_stb_pin} { } CANCommClass::~CANCommClass() { } -bool CANCommClass::begin(int can_bitrate) { - pinMode(PinNameToIndex(PA_13), OUTPUT); //Disable CAN pin - pinMode(PinNameToIndex(PB_8), OUTPUT); - pinMode(PinNameToIndex(PH_13), OUTPUT); +bool CANCommClass::begin(CanBitRate can_bitrate) { + pinMode(PinNameToIndex(_stb), OUTPUT); _enable(); - return mbed::CAN::frequency(can_bitrate); + return _can.begin(can_bitrate); +} + +int CANCommClass::write(CanMsg const & msg) { + return _can.write(msg); +} + +size_t CANCommClass::available() { + return _can.available(); +} + +CanMsg CANCommClass::read() { + return _can.read(); } void CANCommClass::end() { _disable(); + + _can.end(); } void CANCommClass::_enable() { - digitalWrite(PinNameToIndex(PA_13), LOW); + digitalWrite(PinNameToIndex(_stb), LOW); } void CANCommClass::_disable() { - digitalWrite(PinNameToIndex(PA_13), HIGH); + digitalWrite(PinNameToIndex(_stb), HIGH); } CANCommClass MachineControl_CANComm; diff --git a/src/CANCommClass.h b/src/CANCommClass.h index ce9d156..de71595 100644 --- a/src/CANCommClass.h +++ b/src/CANCommClass.h @@ -14,6 +14,7 @@ #include #include #include +#include /* Class ----------------------------------------------------------------------*/ @@ -21,10 +22,9 @@ * @class CANCommClass * @brief Class for managing the CAN Bus communication protocol of the Portenta Machine Control. * - * The `CANCommClass` is a subclass of `mbed::CAN` and provides methods to work with the CAN Bus communication protocol on the Portenta Machine Control board. - * It includes initialization of the corresponding LED for CAN. + * The `CANCommClass` provides methods to work with the CAN Bus communication protocol on the Portenta Machine Control board. */ -class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use Arduino_CAN +class CANCommClass { public: /** * @brief Construct a CANCommClass object. @@ -33,8 +33,9 @@ class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use * * @param can_tx_pin The pin for transmitting data on the CAN Bus. * @param can_rx_pin The pin for receiving data on the CAN Bus. + * @param can_stb_pin The pin to control the standby (low-power) mode of the CAN transceiver. */ - CANCommClass(PinName can_tx_pin = PB_8, PinName can_rx_pin = PH_13); + CANCommClass(PinName can_tx_pin = PB_8, PinName can_rx_pin = PH_13, PinName can_stb_pin = PA_13); /** * @brief Destruct the CANCommClass object. @@ -46,12 +47,40 @@ class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use /** * @brief Begin the CAN communication protocol. * - * This method initializes the CAN communication protocol, including the corresponding LED for CAN. + * This method initializes the CAN communication protocol. * * @param can_bitrate The desired bitrate for the CAN communication protocol. * @return true If the initialization is successful, false otherwise. */ - bool begin(int can_bitrate); + bool begin(CanBitRate can_bitrate); + + /** + * @brief Write a CAN message to the bus. + * + * This method sends a CAN message over the bus. + * + * @param msg The CAN message to be sent, represented by a `CanMsg` object. + * @return The number of bytes sent or <=0 in case of an error. + */ + int write(CanMsg const & msg); + + /** + * @brief Check the number of available CAN messages in the receive buffer. + * + * This method checks the number of CAN messages available to read from the bus. + * + * @return The number of available CAN messages. + */ + size_t available(); + + /** + * @brief Read a CAN message from the bus. + * + * This method reads a CAN message from the receive buffer. + * + * @return The received CAN message as a `CanMsg` object. + */ + CanMsg read(); /** * @brief Close the CAN communication protocol. @@ -61,6 +90,11 @@ class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use void end(); private: + Arduino_CAN _can; + PinName _tx; + PinName _rx; + PinName _stb; + /** * @brief Set the CAN transceiver in Normal mode. * @@ -81,4 +115,4 @@ class CANCommClass: public mbed::CAN { //TODO: Check ARDUINO API VERSION to use extern CANCommClass MachineControl_CANComm; -#endif /* __CAN_COMM_CLASS_H */ \ No newline at end of file +#endif /* __CAN_COMM_CLASS_H */ From 1ab14b276063efdf81814b85ed2a9698ba2f41bf Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Mon, 7 Aug 2023 15:57:29 +0200 Subject: [PATCH 28/47] add pinout file (pins_mc) --- src/AnalogInClass.cpp | 28 ++++++------ src/AnalogInClass.h | 3 +- src/AnalogOutClass.h | 3 +- src/CANCommClass.h | 5 ++- src/DigitalOutputsClass.h | 19 ++++---- src/EncoderClass.h | 5 ++- src/ProgrammableDIOClass.h | 3 +- src/RS485CommClass.cpp | 36 +++++++-------- src/RS485CommClass.h | 4 +- src/RTDTempProbeClass.h | 11 ++--- src/RtcControllerClass.h | 3 +- src/TCTempProbeClass.h | 9 ++-- src/USBClass.cpp | 8 ++-- src/USBClass.h | 7 +-- src/pins_mc.h | 92 ++++++++++++++++++++++++++++++++++++++ 15 files changed, 170 insertions(+), 66 deletions(-) create mode 100644 src/pins_mc.h diff --git a/src/AnalogInClass.cpp b/src/AnalogInClass.cpp index bc529b6..2bdba74 100644 --- a/src/AnalogInClass.cpp +++ b/src/AnalogInClass.cpp @@ -8,20 +8,20 @@ #include "AnalogInClass.h" /* Private defines -----------------------------------------------------------*/ -#define CH0_IN1 PD_4 -#define CH0_IN2 PD_5 -#define CH0_IN3 PE_3 -#define CH0_IN4 PG_3 - -#define CH1_IN1 PD_7 -#define CH1_IN2 PH_6 -#define CH1_IN3 PJ_7 -#define CH1_IN4 PH_15 - -#define CH2_IN1 PH_10 -#define CH2_IN2 PA_4 -#define CH2_IN3 PA_8 -#define CH2_IN4 PC_6 +#define CH0_IN1 MC_AI_CH0_IN1_PIN +#define CH0_IN2 MC_AI_CH0_IN2_PIN +#define CH0_IN3 MC_AI_CH0_IN3_PIN +#define CH0_IN4 MC_AI_CH0_IN4_PIN + +#define CH1_IN1 MC_AI_CH1_IN1_PIN +#define CH1_IN2 MC_AI_CH1_IN2_PIN +#define CH1_IN3 MC_AI_CH1_IN3_PIN +#define CH1_IN4 MC_AI_CH1_IN4_PIN + +#define CH2_IN1 MC_AI_CH2_IN1_PIN +#define CH2_IN2 MC_AI_CH2_IN2_PIN +#define CH2_IN3 MC_AI_CH2_IN3_PIN +#define CH2_IN4 MC_AI_CH2_IN4_PIN /* Functions -----------------------------------------------------------------*/ AnalogInClass::AnalogInClass(PinName ai0_pin, PinName ai1_pin, PinName ai2_pin) diff --git a/src/AnalogInClass.h b/src/AnalogInClass.h index 5d1dca3..3b0421f 100644 --- a/src/AnalogInClass.h +++ b/src/AnalogInClass.h @@ -13,6 +13,7 @@ /* Includes ------------------------------------------------------------------*/ #include #include +#include "pins_mc.h" /* Exported defines ----------------------------------------------------------*/ @@ -36,7 +37,7 @@ class AnalogInClass { * @param ai1_pin The analog pin number of the channel 1 * @param ai2_pin The analog pin number of the channel 2 */ - AnalogInClass(PinName ai0_pin = PC_3C, PinName ai1_pin = PC_2C, PinName ai2_pin = PA_1C); + AnalogInClass(PinName ai0_pin = MC_AI_AI0_PIN, PinName ai1_pin = MC_AI_AI1_PIN, PinName ai2_pin = MC_AI_AI2_PIN); /** * @brief Destruct the AnalogInClass object. diff --git a/src/AnalogOutClass.h b/src/AnalogOutClass.h index e4a9710..6c9efbf 100644 --- a/src/AnalogOutClass.h +++ b/src/AnalogOutClass.h @@ -12,6 +12,7 @@ /* Includes -------------------------------------------------------------------*/ #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -29,7 +30,7 @@ class AnalogOutClass { * @param ao2_pin The analog pin number of the channel 2 * @param ao3_pin The analog pin number of the channel 2 */ - AnalogOutClass(PinName ao0_pin = PJ_11, PinName ao1_pin = PK_1, PinName ao2_pin = PG_7, PinName ao3_pin = PC_7); + AnalogOutClass(PinName ao0_pin = MC_AO_AO0_PIN, PinName ao1_pin = MC_AO_AO1_PIN, PinName ao2_pin = MC_AO_AO2_PIN, PinName ao3_pin = MC_AO_AO3_PIN); /** * @brief Destruct the AnalogOutClass object. diff --git a/src/CANCommClass.h b/src/CANCommClass.h index de71595..78afeda 100644 --- a/src/CANCommClass.h +++ b/src/CANCommClass.h @@ -4,7 +4,7 @@ * @brief Header file for the CANCommClass used to initialize and interact with the CAN Bus communication protocol on the Portenta Machine Control board. * * This library provides a class to manage the CAN Bus communication protocol of the Portenta Machine Control board. - * It allows initializing and interacting with the CAN Bus protocol. The library also initializes the corresponding LED for CAN. + * It allows initializing and interacting with the CAN Bus protocol. */ #ifndef __CAN_COMM_CLASS_H @@ -15,6 +15,7 @@ #include #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -35,7 +36,7 @@ class CANCommClass { * @param can_rx_pin The pin for receiving data on the CAN Bus. * @param can_stb_pin The pin to control the standby (low-power) mode of the CAN transceiver. */ - CANCommClass(PinName can_tx_pin = PB_8, PinName can_rx_pin = PH_13, PinName can_stb_pin = PA_13); + CANCommClass(PinName can_tx_pin = MC_CAN_TX_PIN, PinName can_rx_pin = MC_CAN_RX_PIN, PinName can_stb_pin = MC_CAN_STB_PIN); /** * @brief Destruct the CANCommClass object. diff --git a/src/DigitalOutputsClass.h b/src/DigitalOutputsClass.h index 301dbc3..2ec9959 100644 --- a/src/DigitalOutputsClass.h +++ b/src/DigitalOutputsClass.h @@ -12,6 +12,7 @@ /* Includes -------------------------------------------------------------------*/ #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -36,15 +37,15 @@ class DigitalOutputsClass { * @param do7_pin The pin number for the digital output channel 7. * @param latch_pin The pin number for the latch mode control. */ - DigitalOutputsClass(PinName do0_pin = PI_6, - PinName do1_pin = PH_9, - PinName do2_pin = PJ_9, - PinName do3_pin = PE_2, - PinName do4_pin = PI_3, - PinName do5_pin = PI_2, - PinName do6_pin = PD_3, - PinName do7_pin = PA_14, - PinName latch_pin = PB_2); + DigitalOutputsClass(PinName do0_pin = MC_DO_DO0_PIN, + PinName do1_pin = MC_DO_DO1_PIN, + PinName do2_pin = MC_DO_DO2_PIN, + PinName do3_pin = MC_DO_DO3_PIN, + PinName do4_pin = MC_DO_DO4_PIN, + PinName do5_pin = MC_DO_DO5_PIN, + PinName do6_pin = MC_DO_DO6_PIN, + PinName do7_pin = MC_DO_DO7_PIN, + PinName latch_pin = MC_DO_LATCH_PIN); /** * @brief Destruct the DigitalOutputsClass object. diff --git a/src/EncoderClass.h b/src/EncoderClass.h index 271d82b..ecb18d1 100644 --- a/src/EncoderClass.h +++ b/src/EncoderClass.h @@ -16,6 +16,7 @@ #include "utility/QEI/QEI.h" #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -42,8 +43,8 @@ class EncoderClass { * @param enc1_B_pin Pin assignment for encoder 1 channel B (default: PI_7). * @param enc1_I_pin Pin assignment for encoder 1 Index channel (default: PJ_10). */ - EncoderClass(PinName enc0_A_pin = PJ_8, PinName enc0_B_pin = PH_12, PinName enc0_I_pin = PH_11, - PinName enc1_A_pin = PC_13, PinName enc1_B_pin = PI_7, PinName enc1_I_pin = PJ_10); + EncoderClass(PinName enc0_A_pin = MC_ENC_0A_PIN, PinName enc0_B_pin = MC_ENC_0B_PIN, PinName enc0_I_pin = MC_ENC_0I_PIN, + PinName enc1_A_pin = MC_ENC_1A_PIN, PinName enc1_B_pin = MC_ENC_1B_PIN, PinName enc1_I_pin = MC_ENC_1I_PIN); /** * @brief Destruct the EncoderClass object. diff --git a/src/ProgrammableDIOClass.h b/src/ProgrammableDIOClass.h index a3b3c35..fd5dfc6 100644 --- a/src/ProgrammableDIOClass.h +++ b/src/ProgrammableDIOClass.h @@ -13,6 +13,7 @@ #include "utility/ioexpander/ArduinoIOExpander.h" #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -31,7 +32,7 @@ class ProgrammableDIOClass : public ArduinoIOExpanderClass { * * @param latch_pin The pin number for the latch mode control. */ - ProgrammableDIOClass(PinName latch_pin = PH_14); + ProgrammableDIOClass(PinName latch_pin = MC_PDIO_LATCH_PIN); /** * @brief Destruct the ProgrammableDIOClass object. diff --git a/src/RS485CommClass.cpp b/src/RS485CommClass.cpp index 098f43e..4cd4b75 100644 --- a/src/RS485CommClass.cpp +++ b/src/RS485CommClass.cpp @@ -19,19 +19,19 @@ RS485CommClass::~RS485CommClass() void RS485CommClass::begin(unsigned long baudrate, int predelay, int postdelay) { /* Pinout configuration */ - pinMode(PinNameToIndex(PA_0), OUTPUT); - pinMode(PinNameToIndex(PI_9), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_TX_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_RX_PIN), OUTPUT); - pinMode(PinNameToIndex(PG_9), OUTPUT); - pinMode(PinNameToIndex(PA_10), OUTPUT); - pinMode(PinNameToIndex(PI_15), OUTPUT); - pinMode(PinNameToIndex(PI_14), OUTPUT); - pinMode(PinNameToIndex(PG_14), OUTPUT); - pinMode(PinNameToIndex(PA_9), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_EN_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_RS232_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_FDTERM_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_TERM_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_SLEW_PIN), OUTPUT); + pinMode(PinNameToIndex(MC_RS485_HF_PIN), OUTPUT); /* Turn-off LEDs RS485 */ - digitalWrite(PinNameToIndex(PA_0), LOW); - digitalWrite(PinNameToIndex(PI_9), LOW); + digitalWrite(PinNameToIndex(MC_RS485_TX_PIN), LOW); + digitalWrite(PinNameToIndex(MC_RS485_RX_PIN), LOW); /* Set defaults for RS485 */ _disable(); @@ -58,23 +58,23 @@ void RS485CommClass::end() { } void RS485CommClass::setModeRS232(bool enable) { - digitalWrite(PinNameToIndex(PA_10), enable ? LOW : HIGH); + digitalWrite(PinNameToIndex(MC_RS485_RS232_PIN), enable ? LOW : HIGH); } void RS485CommClass::setYZTerm(bool enable) { - digitalWrite(PinNameToIndex(PI_15), enable ? HIGH : LOW); + digitalWrite(PinNameToIndex(MC_RS485_FDTERM_PIN), enable ? HIGH : LOW); } void RS485CommClass::setABTerm(bool enable) { - digitalWrite(PinNameToIndex(PI_14), enable ? HIGH : LOW); + digitalWrite(PinNameToIndex(MC_RS485_TERM_PIN), enable ? HIGH : LOW); } void RS485CommClass::setSlew(bool enable) { - digitalWrite(PinNameToIndex(PG_14), enable ? LOW : HIGH); + digitalWrite(PinNameToIndex(MC_RS485_SLEW_PIN), enable ? LOW : HIGH); } void RS485CommClass::setFullDuplex(bool enable) { - digitalWrite(PinNameToIndex(PA_9), enable ? LOW : HIGH); + digitalWrite(PinNameToIndex(MC_RS485_HF_PIN), enable ? LOW : HIGH); if (enable) { // RS485 Full Duplex require YZ and AB 120 Ohm termination enabled setYZTerm(true); @@ -83,13 +83,13 @@ void RS485CommClass::setFullDuplex(bool enable) { } void RS485CommClass::_enable() { - digitalWrite(PinNameToIndex(PG_9), HIGH); + digitalWrite(PinNameToIndex(MC_RS485_EN_PIN), HIGH); } void RS485CommClass::_disable() { - digitalWrite(PinNameToIndex(PG_9), LOW); + digitalWrite(PinNameToIndex(MC_RS485_EN_PIN), LOW); } -arduino::UART _UART4_ {PA_0, PI_9, NC, NC}; +arduino::UART _UART4_ {MC_RS485_TX_PIN, MC_RS485_RX_PIN, NC, NC}; RS485CommClass MachineControl_RS485Comm(_UART4_); /**** END OF FILE ****/ \ No newline at end of file diff --git a/src/RS485CommClass.h b/src/RS485CommClass.h index f57d665..b518533 100644 --- a/src/RS485CommClass.h +++ b/src/RS485CommClass.h @@ -14,6 +14,7 @@ #include #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -36,7 +37,8 @@ class RS485CommClass : public RS485Class { * @param rs_de_pin The pin for enabling the RS485 driver. * @param rs_re_pin The pin for setting the RS485 driver in receive or transmit mode. */ - RS485CommClass(arduino::UART& uart_itf, PinName rs_tx_pin = PA_0, PinName rs_de_pin = PI_13, PinName rs_re_pin = PI_10); + RS485CommClass(arduino::UART& uart_itf, PinName rs_tx_pin = MC_RS485_TX_PIN, PinName rs_de_pin = MC_RS485_DE_PIN, PinName rs_re_pin = MC_RS485_RE_PIN); + /** * @brief Destruct the RS485CommClass object. diff --git a/src/RTDTempProbeClass.h b/src/RTDTempProbeClass.h index 1dc94a3..9b1443f 100644 --- a/src/RTDTempProbeClass.h +++ b/src/RTDTempProbeClass.h @@ -15,6 +15,7 @@ #include "utility/THERMOCOUPLE/MAX31855.h" #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -38,11 +39,11 @@ class RTDTempProbeClass: public MAX31865Class { * @param ch_sel2_pin The pin number for the third channel selection bit. * @param rtd_th_pin The pin number for the RTD connection. */ - RTDTempProbeClass(PinName rtd_cs_pin = PA_6, - PinName ch_sel0_pin = PD_6, - PinName ch_sel1_pin = PI_4, - PinName ch_sel2_pin = PG_10, - PinName rtd_th_pin = PC_15); + RTDTempProbeClass(PinName rtd_cs_pin = MC_RTD_CS_PIN, + PinName ch_sel0_pin = MC_RTD_SEL0_PIN, + PinName ch_sel1_pin = MC_RTD_SEL1_PIN, + PinName ch_sel2_pin = MC_RTD_SEL2_PIN, + PinName rtd_th_pin = MC_RTD_TH_PIN); /** * @brief Destruct the RTDTempProbeClass object. diff --git a/src/RtcControllerClass.h b/src/RtcControllerClass.h index 089e737..16cdd6c 100644 --- a/src/RtcControllerClass.h +++ b/src/RtcControllerClass.h @@ -14,6 +14,7 @@ #include "utility/RTC/PCF8563T.h" #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -33,7 +34,7 @@ class RtcControllerClass : public PCF8563TClass { * * @param int_pin The pin number for the interrupt pin (default is PB_9). */ - RtcControllerClass(PinName int_pin = PB_9); + RtcControllerClass(PinName int_pin = MC_RTC_INT_PIN); /** * @brief Destructor for the RtcControllerClass. diff --git a/src/TCTempProbeClass.h b/src/TCTempProbeClass.h index c111d68..7001042 100644 --- a/src/TCTempProbeClass.h +++ b/src/TCTempProbeClass.h @@ -15,6 +15,7 @@ #include "utility/THERMOCOUPLE/MAX31855.h" #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -37,10 +38,10 @@ class TCTempProbeClass: public MAX31855Class { * @param ch_sel1_pin The pin number for the second channel selection bit. * @param ch_sel2_pin The pin number for the third channel selection bit. */ - TCTempProbeClass(PinName tc_cs_pin = PI_0, - PinName ch_sel0_pin = PD_6, - PinName ch_sel1_pin = PI_4, - PinName ch_sel2_pin = PG_10); + TCTempProbeClass(PinName tc_cs_pin = MC_TC_CS_PIN, + PinName ch_sel0_pin = MC_TC_SEL0_PIN, + PinName ch_sel1_pin = MC_TC_SEL1_PIN, + PinName ch_sel2_pin = MC_TC_SEL2_PIN); /** * @brief Destruct the TCTempProbeClass object. diff --git a/src/USBClass.cpp b/src/USBClass.cpp index 6b818c9..44b29de 100644 --- a/src/USBClass.cpp +++ b/src/USBClass.cpp @@ -19,13 +19,13 @@ bool USBClass::begin() { pinMode(_power, OUTPUT); pinMode(_usbflag, INPUT); - _powerEnable(); + _enable(); return true; } void USBClass::end() { - _powerDisable(); + _disable(); } bool USBClass::getFaultStatus() { @@ -41,11 +41,11 @@ bool USBClass::getFaultStatus() { return res; } -void USBClass::_powerEnable() { +void USBClass::_enable() { digitalWrite(_power, LOW); } -void USBClass::_powerDisable() { +void USBClass::_disable() { digitalWrite(_power, HIGH); } diff --git a/src/USBClass.h b/src/USBClass.h index f1f4e44..5f7fd01 100644 --- a/src/USBClass.h +++ b/src/USBClass.h @@ -13,6 +13,7 @@ /* Includes -------------------------------------------------------------------*/ #include #include +#include "pins_mc.h" /* Class ----------------------------------------------------------------------*/ @@ -32,7 +33,7 @@ class USBClass { * @param power_pin The pin number for controlling the power to the USBA VBUS. * @param usbflag_pin The pin number for reading the fault status of the USBA VBUS. */ - USBClass(PinName power_pin = PB_14, PinName usbflag_pin = PB_15); + USBClass(PinName power_pin = MC_USB_PWR_PIN, PinName usbflag_pin = MC_USB_FLAG_PIN); /** * @brief Destruct the USBClass object. @@ -76,14 +77,14 @@ class USBClass { * * This private method is used to enable power to the USBA VBUS. */ - void _powerEnable(); + void _enable(); /** * @brief Disable power to the USBA VBUS. * * This private method is used to disable power to the USBA VBUS. */ - void _powerDisable(); + void _disable(); }; extern USBClass MachineControl_USBController; diff --git a/src/pins_mc.h b/src/pins_mc.h new file mode 100644 index 0000000..d89a75c --- /dev/null +++ b/src/pins_mc.h @@ -0,0 +1,92 @@ +#ifndef __PINS_MC_H +#define __PINS_MC_H + +/** Portenta H7 **/ + +/* AnalogIn */ +#define MC_AI_AI0_PIN PC_3C +#define MC_AI_AI1_PIN PC_2C +#define MC_AI_AI2_PIN PA_1C + +#define MC_AI_CH0_IN1_PIN PD_4 +#define MC_AI_CH0_IN2_PIN PD_5 +#define MC_AI_CH0_IN3_PIN PE_3 +#define MC_AI_CH0_IN4_PIN PG_3 + +#define MC_AI_CH1_IN1_PIN PD_7 +#define MC_AI_CH1_IN2_PIN PH_6 +#define MC_AI_CH1_IN3_PIN PJ_7 +#define MC_AI_CH1_IN4_PIN PH_15 + +#define MC_AI_CH2_IN1_PIN PH_10 +#define MC_AI_CH2_IN2_PIN PA_4 +#define MC_AI_CH2_IN3_PIN PA_8 +#define MC_AI_CH2_IN4_PIN PC_6 + +/* AnalogOut */ +#define MC_AO_AO0_PIN PJ_11 +#define MC_AO_AO1_PIN PK_1 +#define MC_AO_AO2_PIN PG_7 +#define MC_AO_AO3_PIN PC_7 + +/* CAN */ +#define MC_CAN_TX_PIN PB_8 +#define MC_CAN_RX_PIN PH_13 +#define MC_CAN_STB_PIN PA_13 + +/* DigitalOut */ +#define MC_DO_DO0_PIN PI_6 +#define MC_DO_DO1_PIN PH_9 +#define MC_DO_DO2_PIN PJ_9 +#define MC_DO_DO3_PIN PE_2 +#define MC_DO_DO4_PIN PI_3 +#define MC_DO_DO5_PIN PI_2 +#define MC_DO_DO6_PIN PD_3 +#define MC_DO_DO7_PIN PA_14 +#define MC_DO_LATCH_PIN PB_2 + +/* Encoder */ +#define MC_ENC_0A_PIN PJ_8 +#define MC_ENC_0B_PIN PH_12 +#define MC_ENC_0I_PIN PH_11 +#define MC_ENC_1A_PIN PC_13 +#define MC_ENC_1B_PIN PI_7 +#define MC_ENC_1I_PIN PJ_10 + +/* Programmable DIO */ +#define MC_PDIO_LATCH_PIN PH_14 + +/* RS485/232 */ +#define MC_RS485_TX_PIN PA_0 +#define MC_RS485_DE_PIN PI_13 +#define MC_RS485_RE_PIN PI_10 + +#define MC_RS485_RX_PIN PI_9 +#define MC_RS485_EN_PIN PG_9 +#define MC_RS485_RS232_PIN PA_10 +#define MC_RS485_FDTERM_PIN PI_15 +#define MC_RS485_TERM_PIN PI_14 +#define MC_RS485_SLEW_PIN PG_14 +#define MC_RS485_HF_PIN PA_9 + +/* RTC */ +#define MC_RTC_INT_PIN PB_9 + +/* RTD Temperature probe */ +#define MC_RTD_CS_PIN PA_6 +#define MC_RTD_SEL0_PIN PD_6 +#define MC_RTD_SEL1_PIN PI_4 +#define MC_RTD_SEL2_PIN PG_10 +#define MC_RTD_TH_PIN PC_15 + +/* TC Temperature probe */ +#define MC_TC_CS_PIN PI_0 +#define MC_TC_SEL0_PIN MC_RTD_SEL0_PIN +#define MC_TC_SEL1_PIN MC_RTD_SEL1_PIN +#define MC_TC_SEL2_PIN MC_RTD_SEL2_PIN + +/* USB */ +#define MC_USB_PWR_PIN PB_14 +#define MC_USB_FLAG_PIN PB_15 + +#endif /* __PINS_MC_H */ \ No newline at end of file From a9d32a296bad0ffea10bc5272dfaf9929e6799ab Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 8 Aug 2023 11:16:12 +0200 Subject: [PATCH 29/47] RTC alarm example: remove namespace --- examples/RTC_Alarm/RTC_Alarm.ino | 2 -- 1 file changed, 2 deletions(-) diff --git a/examples/RTC_Alarm/RTC_Alarm.ino b/examples/RTC_Alarm/RTC_Alarm.ino index c22a9a4..a9a9250 100644 --- a/examples/RTC_Alarm/RTC_Alarm.ino +++ b/examples/RTC_Alarm/RTC_Alarm.ino @@ -12,8 +12,6 @@ */ #include -using namespace machinecontrol; - int hours = 12; int minutes = 45; int seconds = 57; From f0304db8b29a4cc1b9189a840f9898ad444cc9e9 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 8 Aug 2023 17:03:28 +0200 Subject: [PATCH 30/47] doc: examples --- examples/Analog_Out/Analog_Out.ino | 48 +++++----- .../Analog_input_0_10V/Analog_input_0_10V.ino | 44 +++++---- .../Analog_input_4_20mA.ino | 44 +++++---- .../Analog_input_NTC/Analog_input_NTC.ino | 62 ++++++------- examples/CAN/ReadCan/ReadCan.ino | 34 ++++--- examples/CAN/WriteCan/WriteCan.ino | 53 +++++------ examples/Digital_output/Digital_output.ino | 57 +++++------- .../CombinedIOExpander/CombinedIOExpander.ino | 93 ------------------- .../Digital_input/Digital_input.ino | 27 +++--- .../GPIO_programmable/GPIO_programmable.ino | 32 ++++--- examples/Encoders/Encoders.ino | 19 +++- examples/Ethernet/Ethernet.ino | 24 +++-- examples/RS232/RS232.ino | 48 +++++----- .../RS485_fullduplex/RS485_fullduplex.ino | 46 +++++---- .../RS485_halfduplex/RS485_halfduplex.ino | 45 +++++---- examples/RTC/RTC.ino | 33 ++++--- examples/RTC_Alarm/RTC_Alarm.ino | 48 +++++----- examples/Temp_probes_RTD/Temp_probes_RTD.ino | 34 ++++--- .../Temp_probes_Thermocouples.ino | 36 +++---- examples/USB_host/USB_host.ino | 25 +++-- 20 files changed, 394 insertions(+), 458 deletions(-) delete mode 100644 examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino diff --git a/examples/Analog_Out/Analog_Out.ino b/examples/Analog_Out/Analog_Out.ino index 7c4a9c5..dbe9896 100644 --- a/examples/Analog_Out/Analog_Out.ino +++ b/examples/Analog_Out/Analog_Out.ino @@ -1,32 +1,35 @@ /* - Machine Control - Analog out Example - - This example shows how to use the Analog out channels on - the Machine Control. - The example sets the channels PWM period in the setup, - then loops the channels voltage output value from 0V to 10.4V. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ + * Portenta Machine Control - Analog out + * + * This example demonstrates the utilization of the Analog out channels on the Machine Control. + * The example configures the channels' PWM period in the setup and then iterates through voltage + * output values from 0V to 10.5V in a loop. + * + * The circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include +#define PERIOD_MS 4 /* 4ms - 250Hz */ + float voltage = 0; void setup() { + Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. + } + MachineControl_AnalogOut.begin(); - MachineControl_AnalogOut.setPeriod(0, 4); //4ms - 250Hz - MachineControl_AnalogOut.setPeriod(1, 4); - MachineControl_AnalogOut.setPeriod(2, 4); - MachineControl_AnalogOut.setPeriod(3, 4); - - Serial.begin(9600); - Serial.println("Analog out test"); + MachineControl_AnalogOut.setPeriod(0, PERIOD_MS); + MachineControl_AnalogOut.setPeriod(1, PERIOD_MS); + MachineControl_AnalogOut.setPeriod(2, PERIOD_MS); + MachineControl_AnalogOut.setPeriod(3, PERIOD_MS); } void loop() { @@ -38,10 +41,11 @@ void loop() { Serial.println("All channels set at " + String(voltage) + "V"); voltage = voltage + 0.1; - //Maximum output value is 10.5V + /* Maximum output value is 10.5V */ if (voltage >= 10.5) { voltage = 0; - delay(100); //Additional 100 ms delay introduced to manage 10.5V -> 0V fall time of 150 ms + delay(100); /* Additional 100 ms delay introduced to manage 10.5V -> 0V fall time of 150 ms */ } + delay(100); } diff --git a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino index 4c1b9bf..3573b44 100644 --- a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino +++ b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino @@ -1,48 +1,52 @@ /* - Machine Control - Analog in 0 - 10 V Example + * Portenta Machine Control - Analog in 0-10 V + * + * This example provides the voltage value acquired by the Machine Control. + * For each channel of the ANALOG IN connector, there is a resistor divider made by a 100k and 39k, + * the input voltage is divided by a ratio of 0.28. + * Maximum input voltage is 10V. + * To use the 0V-10V functionality, a 24V supply on the PWR SUPPLY connector is necessary. + * + * The circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This example provides the voltage value acquired by the - Machine Control. For each channel of the ANALOG IN connector, - there is a resistor divider made by a 100k and 39k, - the input voltage is divided by a ratio of 0.28. - Maximum input voltage is 10V. - To use the 0V-10V functionality, a 24V supply on - the PWR SUPPLY connector is necessary. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ #include -float res_divider = 0.28057; -float reference = 3.3; +const float RES_DIVIDER = 0.28057; +const float REFERENCE = 3.3; void setup() { Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. + } + MachineControl_AnalogIn.begin(MCAI_SENSOR_0_10V); } void loop() { float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); - float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535 / res_divider; + float voltage_ch0 = (raw_voltage_ch0 * REFERENCE) / 65535 / RES_DIVIDER; Serial.print("Voltage CH0: "); Serial.print(voltage_ch0, 3); Serial.println("V"); float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); - float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535 / res_divider; + float voltage_ch1 = (raw_voltage_ch1 * REFERENCE) / 65535 / RES_DIVIDER; Serial.print("Voltage CH1: "); Serial.print(voltage_ch1, 3); Serial.println("V"); float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); - float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535 / res_divider; + float voltage_ch2 = (raw_voltage_ch2 * REFERENCE) / 65535 / RES_DIVIDER; Serial.print("Voltage CH2: "); Serial.print(voltage_ch2, 3); Serial.println("V"); + Serial.println(); delay(250); } diff --git a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino index e6fff35..23f6d94 100644 --- a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino +++ b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino @@ -1,47 +1,51 @@ /* - Machine Control - Analog in 4 - 20 mA Example - - This example provides the current value acquired by the - Machine Control. For each channel of the ANALOG IN - connector, there is a 120 ohm resistor to GND. The current - of the 4-20mA sensor flows through it, generating a voltage - which is sampled by the Portenta's ADC. - To use the 4-20mA functionality, a 24V supply on - the PWR SUPPLY connector is necessary. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ + * Portenta Machine Control - Analog in 4-20 mA + * + * This example provides the current value acquired by the Machine Control. + * For each channel of the ANALOG IN connector, a 120 ohm resistor to GND is present. + * The current from the 4-20mA sensor passes through it, generating a voltage + * that is sampled by the Portenta's ADC. + * To use the 4-20mA functionality, a 24V supply on the PWR SUPPLY connector is required. + * + * The circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ + #include #define SENSE_RES 120 -float reference = 3.3; +const float REFERENCE = 3.3; void setup() { Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. + } + MachineControl_AnalogIn.begin(MCAI_SENSOR_4_20MA); } void loop() { float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); - float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535; + float voltage_ch0 = (raw_voltage_ch0 * REFERENCE) / 65535; float current_ch0 = (voltage_ch0 / SENSE_RES) * 1000; Serial.print("Measured Current CH0: "); Serial.print(current_ch0); Serial.println("mA"); float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); - float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535; + float voltage_ch1 = (raw_voltage_ch1 * REFERENCE) / 65535; float current_ch1 = (voltage_ch1 / SENSE_RES) * 1000; Serial.print("Measured Current CH1: "); Serial.print(current_ch1); Serial.println("mA"); + float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); - float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535; + float voltage_ch2 = (raw_voltage_ch2 * REFERENCE) / 65535; float current_ch2 = (voltage_ch2 / SENSE_RES) * 1000; Serial.print("Measured Current CH2: "); Serial.print(current_ch2); diff --git a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino index 8508edb..175771d 100644 --- a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino +++ b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino @@ -1,44 +1,44 @@ /* - Machine Control - Analog in NTC Example + * Portenta Machine Control - Analog in NTC + * + * This example provides the resistance value acquired by the Machine Control. + * A 3V voltage REFERENCE is connected to each channel of the ANALOG IN connector. + * The REFERENCE has a 100k resistor in series, allowing only a low current flow. + * The voltage sampled by the Portenta's ADC is the REFERENCE voltage divided by the voltage divider + * composed of the input resistor and the 100k resistor in series with the voltage REFERENCE. + * The resistor value is calculated by inversely applying the voltage divider formula. + * To use the NTC functionality, a 24V supply on the PWR SUPPLY connector is required. + * + * The circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This example provides the resistance value acquired by the - Machine Control. A 3V voltage reference is connected - to each channel of the ANALOG IN connector. The reference - has a 100k resistor in series, so it can provide only a low - current. - The voltage sampled by the Portenta's ADC is the reference - voltage divided by the voltage divider composed by the - input resistor and the 100k in series to the voltage reference. - The resistor value is calculated by inverting the formula of the - voltage divider. - To use the NTC functionality, the 24V supply on - the PWR SUPPLY connector is necessary. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ #include #define REFERENCE_RES 100000 -float reference = 3.3; -float lowest_voltage = 2.7; +const float REFERENCE = 3.3; +const float LOWEST_VOLTAGE = 2.7; void setup() { Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. + } + MachineControl_AnalogIn.begin(MCAI_SENSOR_NTC); } void loop() { float raw_voltage_ch0 = MachineControl_AnalogIn.read(0); - float voltage_ch0 = (raw_voltage_ch0 * reference) / 65535; + float voltage_ch0 = (raw_voltage_ch0 * REFERENCE) / 65535; float resistance_ch0; Serial.print("Resistance CH0: "); - if (voltage_ch0 < lowest_voltage) { - resistance_ch0 = ((-REFERENCE_RES) * voltage_ch0) / (voltage_ch0 - reference); + if (voltage_ch0 < LOWEST_VOLTAGE) { + resistance_ch0 = ((-REFERENCE_RES) * voltage_ch0) / (voltage_ch0 - REFERENCE); Serial.print(resistance_ch0); Serial.println(" ohm"); } else { @@ -47,11 +47,11 @@ void loop() { } float raw_voltage_ch1 = MachineControl_AnalogIn.read(1); - float voltage_ch1 = (raw_voltage_ch1 * reference) / 65535; + float voltage_ch1 = (raw_voltage_ch1 * REFERENCE) / 65535; float resistance_ch1; Serial.print("Resistance CH1: "); - if (voltage_ch1 < lowest_voltage) { - resistance_ch1 = ((-REFERENCE_RES) * voltage_ch1) / (voltage_ch1 - reference); + if (voltage_ch1 < LOWEST_VOLTAGE) { + resistance_ch1 = ((-REFERENCE_RES) * voltage_ch1) / (voltage_ch1 - REFERENCE); Serial.print(resistance_ch1); Serial.println(" ohm"); } else { @@ -60,11 +60,11 @@ void loop() { } float raw_voltage_ch2 = MachineControl_AnalogIn.read(2); - float voltage_ch2 = (raw_voltage_ch2 * reference) / 65535; + float voltage_ch2 = (raw_voltage_ch2 * REFERENCE) / 65535; float resistance_ch2; Serial.print("Resistance CH2: "); - if (voltage_ch2 < lowest_voltage) { - resistance_ch2 = ((-REFERENCE_RES) * voltage_ch2) / (voltage_ch2 - reference); + if (voltage_ch2 < LOWEST_VOLTAGE) { + resistance_ch2 = ((-REFERENCE_RES) * voltage_ch2) / (voltage_ch2 - REFERENCE); Serial.print(resistance_ch2); Serial.println(" ohm"); } else { diff --git a/examples/CAN/ReadCan/ReadCan.ino b/examples/CAN/ReadCan/ReadCan.ino index 44c4bdb..04db30b 100644 --- a/examples/CAN/ReadCan/ReadCan.ino +++ b/examples/CAN/ReadCan/ReadCan.ino @@ -1,34 +1,32 @@ /* - CAN Read Example + * Portenta Machine Control - CAN Read Example + * + * This sketch shows the usage of the CAN transceiver on the Machine Control + * and demonstrates how to receive data from the RX CAN channel. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to use the CAN transceiver on the Machine - Control and how to receive data from the RX CAN channel. - - Circuit: - - Portenta H7 - - Machine Control - -*/ #include -void setup() -{ +void setup() { Serial.begin(9600); while (!Serial) { ; // wait for serial port to connect. } - if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) - { + if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) { Serial.println("CAN init failed."); - for (;;) {} + while(1) ; } } -void loop() -{ - if (MachineControl_CANComm.available()) - { +void loop() { + if (MachineControl_CANComm.available()) { CanMsg const msg = MachineControl_CANComm.read(); Serial.println(msg); } diff --git a/examples/CAN/WriteCan/WriteCan.ino b/examples/CAN/WriteCan/WriteCan.ino index e6ea617..0b957e0 100644 --- a/examples/CAN/WriteCan/WriteCan.ino +++ b/examples/CAN/WriteCan/WriteCan.ino @@ -1,56 +1,51 @@ /* - CAN Write Example + * Portenta Machine Control - CAN Write Example + * + * This sketch shows the usage of the CAN transceiver on the Machine Control + * and demonstrates how to transmit data from the TX CAN channel. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to use the CAN transceiver on the Machine - Control and how to transmit data from the TX CAN channel. - - Circuit: - - Portenta H7 - - Machine Control - -*/ #include static uint32_t const CAN_ID = 13ul; +static uint32_t msg_cnt = 0; -void setup() -{ +void setup() { Serial.begin(9600); while (!Serial) { ; // wait for serial port to connect. } - if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) - { + if (!MachineControl_CANComm.begin(CanBitRate::BR_500k)) { Serial.println("CAN init failed."); - for (;;) {} + while(1) ; } } -static uint32_t msg_cnt = 0; - -void loop() -{ - /* Assemble a CAN message */ +void loop() { + /* Assemble the CAN message */ uint8_t const msg_data[] = {0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08}; - memcpy((void *)(msg_data + 8), &msg_cnt, sizeof(msg_cnt)); CanMsg msg(CAN_ID, sizeof(msg_data), msg_data); - /* Transmit the CAN message, capture and display an - * error core in case of failure. - */ - if (int const rc = MachineControl_CANComm.write(msg); rc <= 0) - { - Serial.print ("CAN write failed with error code "); + /* Transmit the CAN message */ + int const rc = MachineControl_CANComm.write(msg); + if (rc <= 0) { + Serial.print("CAN write failed with error code: "); Serial.println(rc); - for (;;) { } + while(1) ; } Serial.println("CAN write message!"); - /* Increase the message counter. */ + /* Increase the message counter */ msg_cnt++; - /* Only send one message per second. */ + /* Only send one message per second */ delay(1000); } \ No newline at end of file diff --git a/examples/Digital_output/Digital_output.ino b/examples/Digital_output/Digital_output.ino index 7cf9080..98d76cd 100644 --- a/examples/Digital_output/Digital_output.ino +++ b/examples/Digital_output/Digital_output.ino @@ -1,51 +1,38 @@ /* - Machine Control - Digital Output Example - - This sketch shows how to send values on the - DIGITAL OUT channels on the Machine Control. - Please remember that pin "24V IN" of the connector - DIGITAL_OUTPUTS must be connected to 24V. - The DIGITAL OUT channels are high side switches - capable to handle up to 0.5A. There is an over current - protection that open the channel when the current is - above 0.7A with a +-20% tolerance. - The over current protection can be set to have two - different behaviors, and it is the same for all channels: - 1) Latch mode: when the over current is detected - the channel is opened, and will remain opened until - it is toggled via software. - 2) Auto retry: when the over current is detected - the channel is opened, but after some tens of - milliseconds the channel will automatically try - to close itself again. In case of a persistent - overcurrent the channel will continuously toggle. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ + * Portenta Machine Control - Digital Output Example + * + * This sketch shows how to send values on the DIGITAL OUT channels on the Machine Control. + * The DIGITAL OUT channels are high-side switches capable of handling up to 0.5A. + * There is an overcurrent protection that opens the channel when the current exceeds 0.7A with a +-20% tolerance. + * The overcurrent protection can be set to operate in two different modes for all channels: + * 1) Latch mode: When overcurrent is detected, the channel remains open until toggled via software. + * 2) Auto retry: When overcurrent is detected, the channel opens, but after several tens of milliseconds, + * it attempts to close itself automatically. If overcurrent persists, the channel will continuously toggle. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * NOTE: connect pin "24V IN" of the DIGITAL_OUTPUTS connector to 24V + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include void setup() { Serial.begin(9600); - // The loop starts only when the Serial Monitor is opened. - while (!Serial); + while (!Serial) { + ; // wait for serial port to connect. + } - //Set over current behavior of all channels to latch mode: + //Set over current behavior of all channels to latch mode (true) MachineControl_DigitalOutputs.begin(true); - - // Uncomment this line to set over current behavior of all - // channels to auto retry mode instead of latch mode: - //MachineControl_DigitalOutputs.begin(false); //At startup set all channels to OPEN MachineControl_DigitalOutputs.writeAll(0); } - void loop() { Serial.println("DIGITAL OUT:"); diff --git a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino b/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino deleted file mode 100644 index 8a6dc98..0000000 --- a/examples/Digital_programmable/CombinedIOExpander/CombinedIOExpander.ino +++ /dev/null @@ -1,93 +0,0 @@ -/* - Machine Control - IOExpander Read And Write Example - - This sketch shows how to use the GPIO Expanders on the Machine Control, - how to periodically send a value on the PROGRAMMABLE DIGITAL I/O - output channels and how to periodically read from the PROGRAMMABLE - DIGITAL I/O input channels and DIGITAL INPUT channels. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ - -#include -#include "Wire.h" - -void setup() { - Serial.begin(9600); - while (!Serial); - Wire.begin(); - - if (!MachineControl_DigitalInputs.begin()){ - Serial.println("GPIO expander initialization fail!!"); - } - if (!MachineControl_DigitalProgrammables.begin()){ - Serial.println("GPIO expander initialization fail!!"); - } -} - -void loop() { - // Write the status value to On to Pin 3 - MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_ON); - delay(1000); - - // Read from PROGRAMMABLE DIGITAL I/O Pin 3 - Serial.println("Read IO Pin 03: " + String(MachineControl_DigitalProgrammables.read(IO_READ_CH_PIN_03))); - delay(1000); - - // Read from DIGITAL INPUT Expander Pin 3 - Serial.println("Read DIN Pin 03: " + String(MachineControl_DigitalInputs.read(DIN_READ_CH_PIN_03))); - delay(1000); - - // Write the status value to Off to Pin 3 - MachineControl_DigitalProgrammables.set(IO_WRITE_CH_PIN_03, SWITCH_OFF); - delay(1000); - - Serial.println(); - // Write the status value to On to all the Output Pins - MachineControl_DigitalProgrammables.writeAll(SWITCH_ON_ALL); - - // Reads from all Input Pins - readAll(); - delay(1000); - - // Write the status value to Off all to all the Output Pins - MachineControl_DigitalProgrammables.writeAll(SWITCH_OFF_ALL); - - // Reads from all Input Pins - readAll(); - Serial.println(); - delay(1000); - -} - - -void readAll() { - uint32_t inputs = MachineControl_DigitalProgrammables.readAll(); - Serial.println("CH00: " + String((inputs & (1 << IO_READ_CH_PIN_00)) >> IO_READ_CH_PIN_00)); - Serial.println("CH01: " + String((inputs & (1 << IO_READ_CH_PIN_01)) >> IO_READ_CH_PIN_01)); - Serial.println("CH02: " + String((inputs & (1 << IO_READ_CH_PIN_02)) >> IO_READ_CH_PIN_02)); - Serial.println("CH03: " + String((inputs & (1 << IO_READ_CH_PIN_03)) >> IO_READ_CH_PIN_03)); - Serial.println("CH04: " + String((inputs & (1 << IO_READ_CH_PIN_04)) >> IO_READ_CH_PIN_04)); - Serial.println("CH05: " + String((inputs & (1 << IO_READ_CH_PIN_05)) >> IO_READ_CH_PIN_05)); - Serial.println("CH06: " + String((inputs & (1 << IO_READ_CH_PIN_06)) >> IO_READ_CH_PIN_06)); - Serial.println("CH07: " + String((inputs & (1 << IO_READ_CH_PIN_07)) >> IO_READ_CH_PIN_07)); - Serial.println("CH08: " + String((inputs & (1 << IO_READ_CH_PIN_08)) >> IO_READ_CH_PIN_08)); - Serial.println("CH09: " + String((inputs & (1 << IO_READ_CH_PIN_09)) >> IO_READ_CH_PIN_09)); - Serial.println("CH10: " + String((inputs & (1 << IO_READ_CH_PIN_10)) >> IO_READ_CH_PIN_10)); - Serial.println("CH11: " + String((inputs & (1 << IO_READ_CH_PIN_11)) >> IO_READ_CH_PIN_11)); - Serial.println(); - inputs = MachineControl_DigitalInputs.readAll(); - Serial.println("CH00: " + String((inputs & (1 << DIN_READ_CH_PIN_00)) >> DIN_READ_CH_PIN_00)); - Serial.println("CH01: " + String((inputs & (1 << DIN_READ_CH_PIN_01)) >> DIN_READ_CH_PIN_01)); - Serial.println("CH02: " + String((inputs & (1 << DIN_READ_CH_PIN_02)) >> DIN_READ_CH_PIN_02)); - Serial.println("CH03: " + String((inputs & (1 << DIN_READ_CH_PIN_03)) >> DIN_READ_CH_PIN_03)); - Serial.println("CH04: " + String((inputs & (1 << DIN_READ_CH_PIN_04)) >> DIN_READ_CH_PIN_04)); - Serial.println("CH05: " + String((inputs & (1 << DIN_READ_CH_PIN_05)) >> DIN_READ_CH_PIN_05)); - Serial.println("CH06: " + String((inputs & (1 << DIN_READ_CH_PIN_06)) >> DIN_READ_CH_PIN_06)); - Serial.println("CH07: " + String((inputs & (1 << DIN_READ_CH_PIN_07)) >> DIN_READ_CH_PIN_07)); - Serial.println(); -} diff --git a/examples/Digital_programmable/Digital_input/Digital_input.ino b/examples/Digital_programmable/Digital_input/Digital_input.ino index eccfcef..13024e2 100644 --- a/examples/Digital_programmable/Digital_input/Digital_input.ino +++ b/examples/Digital_programmable/Digital_input/Digital_input.ino @@ -1,24 +1,25 @@ /* - Machine Control - Digital Input Example + * Portenta Machine Control - Digital Input Example + * + * This sketch shows how to periodically read from all the DIGITAL INPUTS channels on the Machine Control. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to periodically read from all the DIGITAL - INPUTS channels on the Machine Control. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ #include -#include "Wire.h" uint16_t readings = 0; void setup() { Serial.begin(9600); - //The loop starts only when the Serial Monitor is opened. - while(!Serial); + while (!Serial) { + ; // wait for serial port to connect. + } + Wire.begin(); if (!MachineControl_DigitalInputs.begin()) { diff --git a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino index 26db172..ae99c90 100644 --- a/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino +++ b/examples/Digital_programmable/GPIO_programmable/GPIO_programmable.ino @@ -1,25 +1,27 @@ /* - Machine Control - IOExpander Read And Write Example + * Portenta Machine Control - IOExpander Read and Write Example + * + * This sketch shows the utilization of the GPIO Expanders on the Machine Control. + * It demonstrates the periodic transmission of values on the PROGRAMMABLE DIGITAL I/O output channels + * and the periodic reading from the PROGRAMMABLE DIGITAL I/O input channels. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to use the GPIO Expanders on the Machine Control, - how to periodically send a value on the PROGRAMMABLE DIGITAL I/O - output channels and how to periodically read from the PROGRAMMABLE - DIGITAL I/O input channels. - - The circuit: - - Portenta H7 - - Machine Control - - This example code is in the public domain. -*/ - #include -#include "Wire.h" void setup() { Serial.begin(9600); - while (!Serial); + while (!Serial) { + ; // wait for serial port to connect. + } + Wire.begin(); + if (!MachineControl_DigitalProgrammables.begin()) { Serial.println("GPIO expander initialization fail!!"); } diff --git a/examples/Encoders/Encoders.ino b/examples/Encoders/Encoders.ino index d843df6..3c3d50b 100644 --- a/examples/Encoders/Encoders.ino +++ b/examples/Encoders/Encoders.ino @@ -1,12 +1,26 @@ +/* + * Portenta Machine Control - Encoder Read Example + * + * This sketch shows the functionality of the encoders on the Machine Control. + * It demonstrates how to periodically read and interpret the values from the two encoder channels. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ + #include void setup() { Serial.begin(9600); - while (!Serial); + while (!Serial) { + ; // wait for serial port to connect. + } } void loop() { - // put your main code here, to run repeatedly: Serial.print("Encoder 0 State: "); Serial.println(MachineControl_Encoders.getCurrentState(0),BIN); Serial.print("Encoder 0 Pulses: "); @@ -22,5 +36,6 @@ void loop() { Serial.print("Encoder 1 Revolutions: "); Serial.println(MachineControl_Encoders.getRevolutions(1)); Serial.println(); + delay(25); } diff --git a/examples/Ethernet/Ethernet.ino b/examples/Ethernet/Ethernet.ino index e1c8438..3857491 100644 --- a/examples/Ethernet/Ethernet.ino +++ b/examples/Ethernet/Ethernet.ino @@ -1,3 +1,17 @@ +/* + * Portenta Machine Control - Ethernet HTTP Request Example + * + * This sketch provides a demonstration of testing the Ethernet port on the Machine Control. + * It shows how to create an HTTP request as a client, sending it to a remote server and + * receiving the response. This example illustrates the basics of making HTTP requests using the Ethernet interface. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ + #include #include #include @@ -9,8 +23,7 @@ unsigned long beginMicros, endMicros; unsigned long byteCount = 0; bool printWebData = true; // set to false for better speed measurement -void setup() -{ +void setup() { Serial.begin(9600); while (!Serial) { ; @@ -26,7 +39,7 @@ void setup() Serial.println(Ethernet.localIP()); } - // give the Ethernet shield a second to initialize: + // give the Ethernet interface a second to initialize: delay(1000); Serial.print("connecting to "); Serial.print(server); @@ -49,11 +62,10 @@ void setup() Serial.println("connection failed"); } - beginMicros = micros(); + beginMicros = micros(); } -void loop() -{ +void loop() { // if there are incoming bytes available // from the server, read them and print them: int len = client.available(); diff --git a/examples/RS232/RS232.ino b/examples/RS232/RS232.ino index cafca98..1a12bf5 100644 --- a/examples/RS232/RS232.ino +++ b/examples/RS232/RS232.ino @@ -1,34 +1,32 @@ /* - RS232 communication - - This sketch shows how to use the SP335ECR1 on the Machine - Control as a RS232 interface, how to periodically send - a string on the RS232 TX channel and how to receive data - from the interface RX channel. - - Circuit: - - Arduino Portenta Machine Control (PMC) - - Device with RS232 interface - - Connect PMC TXN to RS232 Device RXD - - Connect PMC RXP to RS232 Device TXD - - Connect PMC GND to RS232 Device GND - -*/ + * Portenta Machine Control - RS232 Communication Example + * + * This sketch shows the usage of the SP335ECR1 on the Machine Control + * as an RS232 interface. It demonstrates how to periodically send a string on the RS232 TX channel + * and how to receive data from the interface RX channel. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - Device with RS232 interface + * - Connect PMC TXN to RS232 Device RXD + * - Connect PMC RXP to RS232 Device TXD + * - Connect PMC GND to RS232 Device GND + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; - unsigned long counter { 0 }; -void setup() -{ - - Serial.begin(115200); - // Wait for Serial or start after 2.5s - for (auto const timeout = millis() + 2500; !Serial && timeout < millis(); delay(500)) +void setup() { + Serial.begin(9600); + while (!Serial) { ; + } delay(2500); Serial.println("Start RS232 initialization"); @@ -39,8 +37,7 @@ void setup() // - RS485 mode // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled - // Specify baudrate for the communication - MachineControl_RS485Comm.begin(115200); + MachineControl_RS485Comm.begin(115200); // Specify baudrate for the communication // Enable the RS232 mode MachineControl_RS485Comm.setModeRS232(true); @@ -51,8 +48,7 @@ void setup() Serial.println("Initialization done!"); } -void loop() -{ +void loop() { if (MachineControl_RS485Comm.available()) Serial.write(MachineControl_RS485Comm.read()); diff --git a/examples/RS485_fullduplex/RS485_fullduplex.ino b/examples/RS485_fullduplex/RS485_fullduplex.ino index eb10ff0..b3c0389 100644 --- a/examples/RS485_fullduplex/RS485_fullduplex.ino +++ b/examples/RS485_fullduplex/RS485_fullduplex.ino @@ -1,19 +1,19 @@ /* - RS485 Full duplex communication - - This sketch shows how to use the SP335ECR1 on the Machine - Control as a full duplex (AB and YZ) RS485 interface, how to periodically - send a string on the RS485 TX channel and how to receive data - from the interface RX channel. - - Circuit: - - Portenta H7 - - Machine Control - - A Slave device with RS485 interface - - Connect TXP to A(+) and TXN to B(-) - - Connect RXP to Y(+) and RXN to Z(-) - -*/ + * Portenta Machine Control - RS485 Full Duplex Communication Example + * + * This sketch shows the usage of the SP335ECR1 on the Machine Control + * as a full duplex (AB and YZ) RS485 interface. It shows how to periodically send a string + * on the RS485 TX channel and how to receive data from the interface RX channel. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - A Slave device with RS485 interface + * - Connect TXP to A(+) and TXN to B(-) + * - Connect RXP to Y(+) and RXN to Z(-) + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include "Arduino_MachineControl.h" @@ -21,12 +21,12 @@ constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; unsigned long counter = 0; -void setup() -{ - Serial.begin(115200); +void setup() { + Serial.begin(9600); while (!Serial) { - ; // wait for serial port to connect. + ; } + delay(1000); Serial.println("Start RS485 initialization"); @@ -36,8 +36,7 @@ void setup() // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled // Enable the RS485/RS232 system - // Specify baudrate, and preamble and postamble times for RS485 communication - MachineControl_RS485Comm.begin(115200, 0, 500); + MachineControl_RS485Comm.begin(115200, 0, 500); // Specify baudrate, and preamble and postamble times for RS485 communication // Enable Full Duplex mode // This will also enable A/B and Y/Z 120 Ohm termination resistors @@ -49,8 +48,7 @@ void setup() Serial.println("Initialization done!"); } -void loop() -{ +void loop() { if (MachineControl_RS485Comm.available()) Serial.write(MachineControl_RS485Comm.read()); @@ -70,4 +68,4 @@ void loop() sendNow = millis() + sendInterval; } -} +} \ No newline at end of file diff --git a/examples/RS485_halfduplex/RS485_halfduplex.ino b/examples/RS485_halfduplex/RS485_halfduplex.ino index 789584c..414bb89 100644 --- a/examples/RS485_halfduplex/RS485_halfduplex.ino +++ b/examples/RS485_halfduplex/RS485_halfduplex.ino @@ -1,32 +1,31 @@ /* - RS485 Half Duplex communication - - This sketch shows how to use the SP335ECR1 on the Machine - Control as a half duplex (AB) RS485 interface, how to periodically - send a string on the RS485 TX channel and how to receive data - from the interface RX channel. - - Circuit: - - Portenta H7 - - Machine Control - - A Slave device with RS485 interface - - Connect TXP to A(+) and TXN to B(-) - -*/ + * Portenta Machine Control - RS485 Half Duplex Communication Example + * + * This sketch shows the usage of the SP335ECR1 on the Machine Control + * as a half duplex (AB) RS485 interface. It demonstrates how to periodically send a string + * on the RS485 TX channel. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - A Slave device with RS485 interface + * - Connect TXP to A(+) and TXN to B(-) + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include "Arduino_MachineControl.h" constexpr unsigned long sendInterval { 1000 }; unsigned long sendNow { 0 }; - unsigned long counter { 0 }; -void setup() -{ - Serial.begin(115200); +void setup() { + Serial.begin(9600); while (!Serial) { - ; // wait for serial port to connect. + ; } + delay(1000); Serial.println("Start RS485 initialization"); @@ -36,8 +35,7 @@ void setup() // - Half Duplex // - No A/B and Y/Z 120 Ohm termination enabled // Enable the RS485/RS232 system - // Specify baudrate, and preamble and postamble times for RS485 communication - MachineControl_RS485Comm.begin(115200, 0, 500); + MachineControl_RS485Comm.begin(115200, 0, 500); // Specify baudrate, and preamble and postamble times for RS485 communication // Start in receive mode MachineControl_RS485Comm.receive(); @@ -45,8 +43,7 @@ void setup() Serial.println("Initialization done!"); } -void loop() -{ +void loop() { if (MachineControl_RS485Comm.available()) Serial.write(MachineControl_RS485Comm.read()); @@ -66,4 +63,4 @@ void loop() sendNow = millis() + sendInterval; } -} +} \ No newline at end of file diff --git a/examples/RTC/RTC.ino b/examples/RTC/RTC.ino index 496ba3c..87eba27 100644 --- a/examples/RTC/RTC.ino +++ b/examples/RTC/RTC.ino @@ -1,15 +1,16 @@ /* - Machine Control - RTC Example + * Portenta Machine Control - RTC Example + * + * This sketch shows the utilization of the RTC PCF8563T on the Machine + * Control Carrier and demonstrates how to configure the PCF8563T's time registers. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to use the RTC PCF8563T on the Machine - Control Carrier and how to configure the PCF8563T's - time registers. - - Circuit: - - Portenta H7 - - Machine Control - -*/ #include int years = 20; @@ -22,14 +23,14 @@ int seconds = 31; void setup() { Serial.begin(9600); while (!Serial) { - ; // wait for serial port to connect. + ; } - Serial.println("Initialization"); + Serial.print("RTC Initialization"); if(!MachineControl_RTCController.begin()) { - Serial.println("Initialization fail!"); + Serial.println(" fail!"); } - Serial.println("Initialization Done!"); + Serial.println(" done!"); // APIs to set date's fields: years, months, days, hours, minutes and seconds // The RTC time can be set as epoch, using one of the following two options: @@ -45,7 +46,7 @@ void setup() { } void loop() { - // APIs to get date's fields. + // APIs to get date's fields Serial.print("Date: "); Serial.print(MachineControl_RTCController.getYears()); Serial.print("/"); @@ -58,9 +59,11 @@ void loop() { Serial.print(MachineControl_RTCController.getMinutes()); Serial.print(":"); Serial.println(MachineControl_RTCController.getSeconds()); + time_t utc_time = time(NULL); Serial.print("Date as UTC time: "); Serial.println(utc_time); Serial.println(); + delay(1000); } diff --git a/examples/RTC_Alarm/RTC_Alarm.ino b/examples/RTC_Alarm/RTC_Alarm.ino index a9a9250..41277c9 100644 --- a/examples/RTC_Alarm/RTC_Alarm.ino +++ b/examples/RTC_Alarm/RTC_Alarm.ino @@ -1,38 +1,38 @@ /* - Machine Control - RTC Alarm Example + * Portenta Machine Control - RTC Alarm Example + * + * This sketch shows the usage of the RTC PCF8563T on the Machine + * Control Carrier and demonstrates how to configure and utilize the PCF8563T's alarm. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Riccardo Rizzo @Rocketct + */ - This sketch shows how to use the RTC PCF8563T on the Machine - Control Carrier and how to configure and use the PCF8563T's - alarm. - - Circuit: - - Portenta H7 - - Machine Control - -*/ #include int hours = 12; int minutes = 45; int seconds = 57; -void callback_alarm(); - bool alarm_flag = false; +int counter = 1; + +void callback_alarm(); void setup() { Serial.begin(9600); while (!Serial) { - ; // wait for serial port to connect. + ; } - Serial.println("Initialization"); - if (!MachineControl_RTCController.begin()) { - Serial.println("Initialization fail!"); + Serial.print("RTC Initialization"); + if(!MachineControl_RTCController.begin()) { + Serial.println(" fail!"); } - - - Serial.println("Initialization Done!"); + Serial.println(" done!"); // APIs to set date's fields: hours, minutes and seconds MachineControl_RTCController.setHours(hours); @@ -46,10 +46,8 @@ void setup() { // Attach an interrupt to the RTC interrupt pin attachInterrupt(RTC_INT, callback_alarm, FALLING); - - Serial.println(); } -int counter = 1; + void loop() { if (alarm_flag) { Serial.println("Alarm!!"); @@ -64,16 +62,16 @@ void loop() { // MachineControl_RTCController.disableAlarm(); } - // APIs to get date's fields. - //Serial.println(digitalRead(MachineControl_RTCController.int_pin)); + // APIs to get date's fields Serial.print(MachineControl_RTCController.getHours()); Serial.print(":"); Serial.print(MachineControl_RTCController.getMinutes()); Serial.print(":"); Serial.println(MachineControl_RTCController.getSeconds()); + delay(1000); } void callback_alarm () { alarm_flag = true; -} +} \ No newline at end of file diff --git a/examples/Temp_probes_RTD/Temp_probes_RTD.ino b/examples/Temp_probes_RTD/Temp_probes_RTD.ino index ba97b71..7961d30 100644 --- a/examples/Temp_probes_RTD/Temp_probes_RTD.ino +++ b/examples/Temp_probes_RTD/Temp_probes_RTD.ino @@ -1,18 +1,19 @@ /* - Machine Control - Temperature probes RTD example - - This example provides a way to test the 3-wire RTDs - on the Machine control Carrier. It is possible to - acquire 2-wire RTD simply by shorting the RTDx pin - to the TPx pin. The Machine control carrier has on - board a precise 400 ohm 0.1% reference resistor which - is used as a reference by the MAX31865. - - The circuit: - - Portenta H7 - - Portenta Machine Control Carrier - - 3-wire RTD or 2-wire RTD -*/ + * Portenta Machine Control - Temperature Probes RTD Example + * + * This example provides a method to test the 3-wire RTDs + * on the Machine Control Carrier. It is also possible to + * acquire 2-wire RTDs by shorting the RTDx pin to the TPx pin. + * The Machine Control Carrier features a precise 400 ohm 0.1% reference resistor, + * which serves as a reference for the MAX31865. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - 3-wire RTD or 2-wire RTD + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include @@ -24,7 +25,10 @@ void setup() { Serial.begin(9600); - Serial.println("MAX31865 PT100 Sensor Test!"); + while (!Serial) { + ; + } + MachineControl_RTDTempProbe.begin(THREE_WIRE); } diff --git a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino index 9e1ab4a..33689a1 100644 --- a/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino +++ b/examples/Temp_probes_Thermocouples/Temp_probes_Thermocouples.ino @@ -1,25 +1,27 @@ /* - Machine Control - Thermocouples Read Sensors - - This example reads the temperatures measured by the thermocouples - connected to the Machine Control Carrier's temp probe inputs and prints - them to the Serial Monitor once a second. - - The circuit: - - Portenta H7 - - Portenta Machine Control Carrier - - Two K Type thermocouple temperature sensors connected to - TEMP PROBES CH0 and CH1 on the Machine Control - - A J Type thermocouple temperature sensor connected to - TEMP PROBES CH3 on the Machine Control - - This example code is in the public domain. -*/ + * Portenta Machine Control - Thermocouples Temperature Reading Example + * + * This example reads the temperatures measured by the thermocouples + * connected to the temp probe inputs on the Portenta Machine Control Carrier. + * It prints the temperature values to the Serial Monitor every second. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - Two K Type thermocouple temperature sensors connected to TEMP PROBES CH0 and CH1 + * - A J Type thermocouple temperature sensor connected to TEMP PROBES CH3 + * + * Initial author: Riccardo Rizzo @Rocketct + */ #include void setup() { Serial.begin(9600); + while (!Serial) { + ; + } + // Initialize temperature probes MachineControl_TCTempProbe.begin(); Serial.println("Temperature probes initialization done"); @@ -51,4 +53,4 @@ void loop() { Serial.println(); Serial.println(); -} +} \ No newline at end of file diff --git a/examples/USB_host/USB_host.ino b/examples/USB_host/USB_host.ino index af92861..61e74da 100644 --- a/examples/USB_host/USB_host.ino +++ b/examples/USB_host/USB_host.ino @@ -1,16 +1,27 @@ +/* + * Portenta Machine Control - USB Port Usage Example + * + * This example shows how to utilize the USB port on the Portenta Machine Control. + * + * Circuit: + * - Portenta H7 + * - Portenta Machine Control + * - USB device (e.g., keyboard, mouse, etc.) + * + * Initial author: Riccardo Rizzo @Rocketct + */ + #include -#include +#include #include "TUSB_helpers.h" -// Redirect log output from MbedOS and low-level libraries to Serial REDIRECT_STDOUT_TO(Serial); USBHost usb; -void setup() -{ - Serial1.begin(115200); +void setup() { + Serial1.begin(9600); MachineControl_USBController.begin(); usb.Init(USB_CORE_ID_FS, class_table); @@ -18,6 +29,4 @@ void setup() void loop() { usb.Task(); -} - - +} \ No newline at end of file From 228205c4adcfdf5a33945e18d43f795fd6a13be3 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 9 Aug 2023 12:34:49 +0200 Subject: [PATCH 31/47] MAX31855: fix constructor param --- src/utility/THERMOCOUPLE/MAX31855.cpp | 2 +- src/utility/THERMOCOUPLE/MAX31855.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/utility/THERMOCOUPLE/MAX31855.cpp b/src/utility/THERMOCOUPLE/MAX31855.cpp index 4e86718..80f580e 100644 --- a/src/utility/THERMOCOUPLE/MAX31855.cpp +++ b/src/utility/THERMOCOUPLE/MAX31855.cpp @@ -38,7 +38,7 @@ const MAX31855Class::coefftable MAX31855Class::CoeffK[]; const MAX31855Class::coefftable MAX31855Class::InvCoeffJ[]; const MAX31855Class::coefftable MAX31855Class::InvCoeffK[]; -MAX31855Class::MAX31855Class(int cs, SPIClass& spi) : +MAX31855Class::MAX31855Class(PinName cs, SPIClass& spi) : _cs(cs), _spi(&spi), _spiSettings(4000000, MSBFIRST, SPI_MODE0), diff --git a/src/utility/THERMOCOUPLE/MAX31855.h b/src/utility/THERMOCOUPLE/MAX31855.h index c2c5380..389e5b4 100644 --- a/src/utility/THERMOCOUPLE/MAX31855.h +++ b/src/utility/THERMOCOUPLE/MAX31855.h @@ -29,7 +29,7 @@ class MAX31855Class { public: - MAX31855Class(int cs = 7, SPIClass& spi = SPI); + MAX31855Class(PinName cs = PI_0, SPIClass& spi = SPI); int begin(); void end(); From fe62475fb41fc78380461e0db9ed2b8bd6f87a93 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 11 Aug 2023 10:23:23 +0200 Subject: [PATCH 32/47] doc: update README --- README.md | 16 ++++++++-------- docs/README.md | 10 ++++++++++ 2 files changed, 18 insertions(+), 8 deletions(-) create mode 100644 docs/README.md diff --git a/README.md b/README.md index 1cf6533..8c74f0b 100644 --- a/README.md +++ b/README.md @@ -1,18 +1,17 @@ -# Portenta Machine Control Library for Arduino +# 🏭 Library for Portenta Machine Control -[![Check Arduino status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/check-arduino.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/check-arduino.yml) -[![Compile Examples status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml) -[![Spell Check status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml) +The Arduino Portenta Machine Control is a versatile industrial unit for driving machinery. It offers soft-PLC control, diverse I/O options, and flexible network connectivity. -Arduino Library for the Portenta Machine Control +The Machine Control library enables efficient management of the features of the Portenta Machine Control board. -The Portenta Machine Control enhances existing products with minimal effort, allowing companies to implement a standard platform across different equipment models. It is now easy to create an infrastructure of interconnected machines, which can be controlled onsite or via the cloud when needed; moreover, human-machine interaction can be further enahnced via mobile apps thanks to BLE connectivity. +📦 For more information about this product: +https://www.arduino.cc/pro/hardware/product/portenta-machine-control -For more information about this library please visit us at https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol/ -For more information about this product: https://www.arduino.cc/pro/hardware/product/portenta-machine-control +📖 For more information about this library please read the documentation [here](./docs/). ## License +``` Copyright (c) 2021 Arduino SA. All rights reserved. This library is free software; you can redistribute it and/or @@ -28,3 +27,4 @@ Lesser General Public License for more details. You should have received a copy of the GNU Lesser General Public License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +``` \ No newline at end of file diff --git a/docs/README.md b/docs/README.md new file mode 100644 index 0000000..8b61b98 --- /dev/null +++ b/docs/README.md @@ -0,0 +1,10 @@ +# Portenta Machine Control Library + +[![Check Arduino status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/check-arduino.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/check-arduino.yml) +[![Compile Examples status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml) +[![Spell Check status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml) + +[![License](https://img.shields.io/badge/License-LGPLv3-blue.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt) + +📚 For more information about this library please visit us at: +https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol \ No newline at end of file From ce11f9b2a564b6c29e78ae5ce910f9ee290e57c0 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 11 Aug 2023 10:53:20 +0200 Subject: [PATCH 33/47] doc: removed unused keywords --- keywords.txt | 96 +--------------------------------------------------- 1 file changed, 1 insertion(+), 95 deletions(-) diff --git a/keywords.txt b/keywords.txt index 026f3ca..00f390c 100644 --- a/keywords.txt +++ b/keywords.txt @@ -5,108 +5,14 @@ ####################################### Arduino_MachineControl KEYWORD1 -machinecontrol KEYWORD1 -temp_probes KEYWORD1 -comm_protocols KEYWORD1 -analog_in KEYWORD1 -analog_out KEYWORD1 -encoders KEYWORD1 -digital_outputs KEYWORD1 -digital_inputs KEYWORD1 -digital_programmables KEYWORD1 -rtc_controller KEYWORD1 - -can KEYWORD1 -rtd KEYWORD1 -tc KEYWORD1 ####################################### # Methods and Functions (KEYWORD2) ####################################### begin KEYWORD2 -end KEYWORD2 - -selectChannel KEYWORD2 -enableTC KEYWORD2 -enableRTD KEYWORD2 -disableCS KEYWORD2 - -enableCAN KEYWORD2 -disableCAN KEYWORD2 - -set0_10V KEYWORD2 -set4_20mA KEYWORD2 -setNTC KEYWORD2 - -read KEYWORD2 -stop KEYWORD2 - -write KEYWORD2 -period_ms KEYWORD2 - -init KEYWORD2 -setAll KEYWORD2 -set KEYWORD2 -setLatch KEYWORD2 -setRetry KEYWORD2 -getMonths KEYWORD2 -setMonths KEYWORD2 - -enableAlarm KEYWORD2 -disableAlarm KEYWORD2 -clearAlarm KEYWORD2 -setMinuteAlarm KEYWORD2 -disableMinuteAlarm KEYWORD2 -setHourAlarm KEYWORD2 -disableHourAlarm KEYWORD2 -setDayAlarm KEYWORD2 -disableDayAlarm KEYWORD2 +end KEYWORD2 ####################################### # Constants (LITERAL1) ####################################### - -APPEND LITERAL1 - -IO_ADD LITERAL1 -DIN_ADD LITERAL1 - -SWITCH_ON HIGH LITERAL1 -SWITCH_OFF LOW LITERAL1 - -IO_WRITE_CH_PIN_00 LITERAL1 -IO_WRITE_CH_PIN_01 LITERAL1 -IO_WRITE_CH_PIN_02 LITERAL1 -IO_WRITE_CH_PIN_03 LITERAL1 -IO_WRITE_CH_PIN_04 LITERAL1 -IO_WRITE_CH_PIN_05 LITERAL1 -IO_WRITE_CH_PIN_06 LITERAL1 -IO_WRITE_CH_PIN_07 LITERAL1 -IO_WRITE_CH_PIN_08 LITERAL1 -IO_WRITE_CH_PIN_09 LITERAL1 -IO_WRITE_CH_PIN_10 LITERAL1 -IO_WRITE_CH_PIN_11 LITERAL1 -IO_READ_CH_PIN_00 LITERAL1 -IO_READ_CH_PIN_01 LITERAL1 -IO_READ_CH_PIN_02 LITERAL1 -IO_READ_CH_PIN_03 LITERAL1 -IO_READ_CH_PIN_04 LITERAL1 -IO_READ_CH_PIN_05 LITERAL1 -IO_READ_CH_PIN_06 LITERAL1 -IO_READ_CH_PIN_07 LITERAL1 -IO_READ_CH_PIN_08 LITERAL1 -IO_READ_CH_PIN_09 LITERAL1 -IO_READ_CH_PIN_10 LITERAL1 -IO_READ_CH_PIN_11 LITERAL1 -DIN_READ_CH_PIN_00 LITERAL1 -DIN_READ_CH_PIN_01 LITERAL1 -DIN_READ_CH_PIN_02 LITERAL1 -DIN_READ_CH_PIN_03 LITERAL1 -DIN_READ_CH_PIN_04 LITERAL1 -DIN_READ_CH_PIN_05 LITERAL1 -DIN_READ_CH_PIN_06 LITERAL1 -DIN_READ_CH_PIN_07 LITERAL1 - -PROBE_K LITERAL1 -#define LITERAL1 From c4c119b4ccf7e852ee4841baa848095a05561eb4 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 11 Aug 2023 12:29:11 +0200 Subject: [PATCH 34/47] doc: update docs/README.md --- docs/README.md | 90 ++++++++++++++++++++++++++++++++++++++++++++++++-- docs/api.md | 0 2 files changed, 88 insertions(+), 2 deletions(-) create mode 100644 docs/api.md diff --git a/docs/README.md b/docs/README.md index 8b61b98..64b37ff 100644 --- a/docs/README.md +++ b/docs/README.md @@ -4,7 +4,93 @@ [![Compile Examples status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/compile-examples.yml) [![Spell Check status](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml/badge.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/actions/workflows/spell-check.yml) -[![License](https://img.shields.io/badge/License-LGPLv3-blue.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt) +[![License](https://img.shields.io/badge/License-LGPLv2.1-blue.svg)](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt) + +The Portenta Machine Control Library is a C++ library designed to efficiently manage the functionalities of the Portenta Machine Control board. It provides extensive support for inputs such as digital, analog, and encoder signals, while offering outputs including digital and analog signals. This library also menages communication through protocols like CAN-BUS and serial ports, and allows connectivity via Ethernet, USB, Wi-Fi, and Bluetooth Low Energy. + +The library empowers users to easily initialize, control, and access the diverse functionalities of the Portenta Machine Control, enhancing its capability and adaptability for industrial applications. 📚 For more information about this library please visit us at: -https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol \ No newline at end of file +https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol + +## Features + +- Manages input signals, including: + - 8 digital inputs at 24Vdc + - 2 channels for encoder readings + - 3 analog inputs for PT100/J/K temperature probes + - 3 analog inputs for 4-20mA/0-10V/NTC signals + +- Manages output signals, including: + - 8 digital outputs at 24Vdc + - 4 analog outputs at 0-10V + +- Provides control for other I/O: + - 12 programmable digital I/O at 24V + +- Supports various Communication Protocols: + - CAN-BUS + - Serial protocols (RS232/RS422/RS485) + +- Supports versatile connectivity options: + - Ethernet + - USB + - Bluetooth Low Energy + - Wi-Fi + +- Handles RTC (Real-Time Clock) functionality + +## Usage + +To use this library, you must have a properly powered Portenta Machine Control board running at 24V. Once you have ensured the correct power supply and established the connection, you can include the machine control library in your Arduino sketch and use its functions to manage the board features. + +Here is a minimal example to control a digital output: + +```cpp +// Include the Arduino MachineControl library +#include + +void setup() { + // Initialize the digital outputs module of the MachineControl library + MachineControl_DigitalOutputs.begin(); +} + +void loop() { + // Turn on the digital output at channel 0 + MachineControl_DigitalOutputs.write(0, HIGH); + delay(1000); + // Turn off the digital output at channel 0 + MachineControl_DigitalOutputs.write(0, LOW); + delay(1000); +} +``` + +## Examples + +- **Analog_input_0_10V:** This example demonstrates how to read analog input signals in the 0-10V range. +- **Analog_input_4_20mA:** This example demonstrates how to read analog input signals in the 4-20mA range. +- **Analog_input_NTC:** This example shows reading analog input signals from NTC temperature probes. +- **Analog_Out:** This example shows how to control analog output signals. +- **ReadCan:** This example demonstrates how to read data using the CAN-BUS communication protocol. +- **WriteCan:** This example demonstrates how to send data using the CAN-BUS communication protocol. +- **Digital_output:** This example shows how to control digital output signals. +- **Digital_input:** This example shows how to read digital input signals. +- **GPIO_programmable:** This example demonstrates the usage of programmable digital I/O pins. +- **Encoders:** This example shows how to work with encoder readings. +- **Ethernet:** This example shows how to establish Ethernet communication and connects to a website. +- **RS232:** This example demonstrates serial communication using the RS232 protocol. +- **RS485_fullduplex:** This example demonstrates full-duplex serial communication using the RS485 protocol. +- **RS485_halfduplex:** This example demonstrates half-duplex serial communication using the RS485 protocol. +- **RTC:** This example shows how to interact with the Real-Time Clock functionality. +- **RTC_Alarm:** This example demonstrates how to set up and utilize RTC alarms. +- **Temp_probes_RTD:** This example demonstrates the temperature probe readings using RTD sensors. +- **Temp_probes_Thermocouples:** This example demonstrates the temperature probe readings using thermocouple sensors. +- **USB_host:** This example shows the USB host functionality. + +## API + +The API documentation can be found [here](./api.md). + +## License + +This library is released under the [LGPLv2.1 license](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt). \ No newline at end of file diff --git a/docs/api.md b/docs/api.md new file mode 100644 index 0000000..e69de29 From c8761a6024f14da5b562beca4ddb91a3e90640bc Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 11 Aug 2023 12:49:53 +0200 Subject: [PATCH 35/47] doc: add example folder links --- docs/README.md | 41 ++++++++++++++++++++++------------------- 1 file changed, 22 insertions(+), 19 deletions(-) diff --git a/docs/README.md b/docs/README.md index 64b37ff..9e7ff7a 100644 --- a/docs/README.md +++ b/docs/README.md @@ -67,25 +67,28 @@ void loop() { ## Examples -- **Analog_input_0_10V:** This example demonstrates how to read analog input signals in the 0-10V range. -- **Analog_input_4_20mA:** This example demonstrates how to read analog input signals in the 4-20mA range. -- **Analog_input_NTC:** This example shows reading analog input signals from NTC temperature probes. -- **Analog_Out:** This example shows how to control analog output signals. -- **ReadCan:** This example demonstrates how to read data using the CAN-BUS communication protocol. -- **WriteCan:** This example demonstrates how to send data using the CAN-BUS communication protocol. -- **Digital_output:** This example shows how to control digital output signals. -- **Digital_input:** This example shows how to read digital input signals. -- **GPIO_programmable:** This example demonstrates the usage of programmable digital I/O pins. -- **Encoders:** This example shows how to work with encoder readings. -- **Ethernet:** This example shows how to establish Ethernet communication and connects to a website. -- **RS232:** This example demonstrates serial communication using the RS232 protocol. -- **RS485_fullduplex:** This example demonstrates full-duplex serial communication using the RS485 protocol. -- **RS485_halfduplex:** This example demonstrates half-duplex serial communication using the RS485 protocol. -- **RTC:** This example shows how to interact with the Real-Time Clock functionality. -- **RTC_Alarm:** This example demonstrates how to set up and utilize RTC alarms. -- **Temp_probes_RTD:** This example demonstrates the temperature probe readings using RTD sensors. -- **Temp_probes_Thermocouples:** This example demonstrates the temperature probe readings using thermocouple sensors. -- **USB_host:** This example shows the USB host functionality. +## Examples + +- **[Analog_input_0_10V](../examples/Analog_input/Analog_input_0_10V):** This example demonstrates how to read analog input signals in the 0-10V range. +- **[Analog_input_4_20mA](../examples/Analog_input/Analog_input_4_20mA):** This example demonstrates how to read analog input signals in the 4-20mA range. +- **[Analog_input_NTC](../examples/Analog_input/Analog_input_NTC):** This example shows reading analog input signals from NTC temperature probes. +- **[Analog_Out](../examples/Analog_Out):** This example shows how to control analog output signals. +- **[ReadCan](../examples/CAN/ReadCan):** This example demonstrates how to read data using the CAN-BUS communication protocol. +- **[WriteCan](../examples/CAN/WriteCan):** This example demonstrates how to send data using the CAN-BUS communication protocol. +- **[Digital_output](../examples/Digital_output):** This example shows how to control digital output signals. +- **[Digital_input](../examples/Digital_programmable/Digital_input):** This example shows how to read digital input signals. +- **[GPIO_programmable](../examples/Digital_programmable/GPIO_programmable):** This example demonstrates the usage of programmable digital I/O pins. +- **[Encoders](../examples/Encoders):** This example shows how to work with encoder readings. +- **[Ethernet](../examples/Ethernet):** This example shows how to establish Ethernet communication and connects to a website. +- **[RS232](../examples/RS232):** This example demonstrates serial communication using the RS232 protocol. +- **[RS485_fullduplex](../examples/RS485_fullduplex):** This example demonstrates full-duplex serial communication using the RS485 protocol. +- **[RS485_halfduplex](../examples/RS485_halfduplex):** This example demonstrates half-duplex serial communication using the RS485 protocol. +- **[RTC](../examples/RTC):** This example shows how to interact with the Real-Time Clock functionality. +- **[RTC_Alarm](../examples/RTC_Alarm):** This example demonstrates how to set up and utilize RTC alarms. +- **[Temp_probes_RTD](../examples/Temp_probes_RTD):** This example demonstrates the temperature probe readings using RTD sensors. +- **[Temp_probes_Thermocouples](../examples/Temp_probes_Thermocouples):** This example demonstrates the temperature probe readings using thermocouple sensors. +- **[USB_host](../examples/USB_host):** This example shows the USB host functionality. + ## API From 83e97e306799d74e62b0987d2b3c29d9fa5a7ce1 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 11 Aug 2023 14:41:30 +0200 Subject: [PATCH 36/47] doc: update docs/README.md --- docs/README.md | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/docs/README.md b/docs/README.md index 9e7ff7a..ac53a00 100644 --- a/docs/README.md +++ b/docs/README.md @@ -28,11 +28,11 @@ https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol - Provides control for other I/O: - 12 programmable digital I/O at 24V -- Supports various Communication Protocols: +- Supports various communication protocols: - CAN-BUS - Serial protocols (RS232/RS422/RS485) -- Supports versatile connectivity options: +- Supports connectivity options: - Ethernet - USB - Bluetooth Low Energy @@ -67,8 +67,6 @@ void loop() { ## Examples -## Examples - - **[Analog_input_0_10V](../examples/Analog_input/Analog_input_0_10V):** This example demonstrates how to read analog input signals in the 0-10V range. - **[Analog_input_4_20mA](../examples/Analog_input/Analog_input_4_20mA):** This example demonstrates how to read analog input signals in the 4-20mA range. - **[Analog_input_NTC](../examples/Analog_input/Analog_input_NTC):** This example shows reading analog input signals from NTC temperature probes. @@ -89,7 +87,6 @@ void loop() { - **[Temp_probes_Thermocouples](../examples/Temp_probes_Thermocouples):** This example demonstrates the temperature probe readings using thermocouple sensors. - **[USB_host](../examples/USB_host):** This example shows the USB host functionality. - ## API The API documentation can be found [here](./api.md). From 26bdb2a49bc62769853cc4b13914dd6d017d1692 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 17 Aug 2023 11:59:32 +0200 Subject: [PATCH 37/47] doc: update API.md --- docs/api.md | 171 ++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 171 insertions(+) diff --git a/docs/api.md b/docs/api.md index e69de29..48d98f6 100644 --- a/docs/api.md +++ b/docs/api.md @@ -0,0 +1,171 @@ +# Summary + + Members | Descriptions +--------------------------------------------|------------------------------------------ +`class` [`AnalogInClass`](#class-analoginclass) | Class for the Analog IN connector of the Portenta Machine Control. +`class` [`AnalogOutClass`](#class-analogoutclass) | Class for the Analog OUT connector of the Portenta Machine Control. +`class` [`CANCommClass`](#class-cancommclass) | Class for managing the CAN Bus communication protocol of the Portenta Machine Control. +`class` [`DigitalOutputsClass`](#class-digitaloutputsclass) | Class for the Digital Output connector of the Portenta Machine Control. +`class` [`EncoderClass`](#class-encoderclass) | Class for the encoder module of the Portenta Machine Control. +`class` [`ProgrammableDINClass`](#class-programmabledinclass) | Class for the Programmable Digital Input connector of the Portenta Machine Control. +`class` [`ProgrammableDIOClass`](#class-programmabledioclass) | Class for the Programmable Digital IO connector of the Portenta Machine Control. +`class` [`RS485CommClass`](#class-rs485commclass) | Class for managing the RS485 and RS232 communication protocols of the Portenta Machine Control. +`class` [`RTDTempProbeClass`](#class-rtdtempprobeclass) | Class for managing the Resistance Temperature Detector (RTD) temperature sensor connector of the Portenta Machine Control. +`class` [`RtcControllerClass`](#class-rtccontrollerclass) | Class for controlling the PCF8563T RTC of the Portenta Machine Control. +`class` [`TCTempProbeClass`](#class-tctempprobeclass) | Class for managing the Thermocouple (TC) temperature sensor connector of the Portenta Machine Control. +`class` [`USBClass`](#class-usbclass) | Class for managing the USB functionality of the Portenta Machine Control. + +# class `AnalogInClass` +Class for the Analog IN connector of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`AnalogInClass`](#public-analoginclasspinname-ai0_pin--mc_ai_ai0_pin-pinname-ai1_pin--mc_ai_ai1_pin-pinname-ai2_pin--mc_ai_ai2_pin)`(PinName ai0_pin, PinName ai1_pin, PinName ai2_pin)` | Construct an Analog Input reader for the Portenta Machine Control. +`public ` [`~AnalogInClass`](#public-analoginclass)`()` | Destruct the AnalogInClass object. +`public bool` [`begin`](#public-bool-beginint-sensor_type-int-res_bits--16)`(int sensor_type, int res_bits)` | Initialize the analog reader, configure the sensor type and read resolution. +`public uint16_t` [`read`](#public-uint16_t-readint-channel)`(int channel)` | Read the sampled voltage from the selected channel. + +# class `AnalogOutClass` +Class for the Analog OUT connector of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`AnalogOutClass`](#public-analogoutclasspinname-ao0_pin--mc_ao_ao0_pin-pinname-ao1_pin--mc_ao_ao1_pin-pinname-ao2_pin--mc_ao_ao2_pin-pinname-ao3_pin--mc_ao_ao3_pin)`(PinName ao0_pin, PinName ao1_pin, PinName ao2_pin, PinName ao3_pin)` | Construct an Analog Output writer for the Portenta Machine Control. +`public ` [`~AnalogOutClass`](#public-analogoutclass)`()` | Destruct the AnalogOutClass object. +`public bool` [`begin`](#public-bool-begin)`()` | Initialize the PWM, configure the default frequency for all channels (500Hz). +`public void` [`setPeriod`](#public-void-setperiodint-channel-uint8_t-period_ms)`(int channel, uint8_t period_ms)` | Set the PWM period (frequency) on the selected channel. +`public void` [`write`](#public-void-writeint-channel-float-voltage)`(int channel, float voltage)` | Set output voltage value on the selected channel. + +# class `CANCommClass` +Class for managing the CAN Bus communication protocol of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`CANCommClass`](#public-cancommclasspinname-can_tx_pin--mc_can_tx_pin-pinname-can_rx_pin--mc_can_rx_pin-pinname-can_stb_pin--mc_can_stb_pin)`(PinName can_tx_pin, PinName can_rx_pin, PinName can_stb_pin)` | Construct a CANCommClass object. +`public ` [`~CANCommClass`](#public-cancommclass)`()` | Destruct the CANCommClass object. +`public bool` [`begin`](#public-bool-begincanbitrate-can_bitrate)`(CanBitRate can_bitrate)` | Begin the CAN communication protocol. +`public int` [`write`](#public-int-writecanmsg-const--msg)`(CanMsg const & msg)` | Write a CAN message to the bus. +`public size_t` [`available`](#public-size_t-available)`()` | Check the number of available CAN messages in the receive buffer. +`public CanMsg` [`read`](#public-canmsg-read)`()` | Read a CAN message from the bus. +`public void` [`end`](#public-void-end)`()` | Close the CAN communication protocol. + +# class `DigitalOutputsClass` +Class for the Digital Output connector of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`DigitalOutputsClass`](#public-digitaloutputsclasspinname-do0_pin--mc_do_do0_pin-pinname-do1_pin--mc_do_do1_pin-pinname-do2_pin--mc_do_do2_pin-pinname-do3_pin--mc_do_do3_pin-pinname-do4_pin--mc_do_do4_pin-pinname-do5_pin--mc_do_do5_pin-pinname-do6_pin--mc_do_do6_pin-pinname-do7_pin--mc_do_do7_pin-pinname-latch_pin--mc_do_latch_pin)`(PinName do0_pin, PinName do1_pin, PinName do2_pin, PinName do3_pin, PinName do4_pin, PinName do5_pin, PinName do6_pin, PinName do7_pin, PinName latch_pin)` | Construct a DigitalOutputsClass object. +`public ` [`~DigitalOutputsClass`](#public-digitaloutputsclass)`()` | Destruct the DigitalOutputsClass object. +`public bool` [`begin`](#public-bool-beginbool-latch_mode--true)`(bool latch_mode = true)` | Initialize the DigitalOutputs module with the specified latch mode. +`public void` [`write`](#public-void-writeuint8_t-channel-pinstatus-val)`(uint8_t channel, PinStatus val)` | Write the output value for the given channel. +`public void` [`writeAll`](#public-void-writealluint8_t-val_mask)`(uint8_t val_mask)` | Set the state of all digital outputs simultaneously. + +# class `EncoderClass` +Class for managing Quadrature Encoder Interface devices of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`EncoderClass`](#public-encoderclasspinname-enc0_a_pin--mc_enc_0a_pin-pinname-enc0_b_pin--mc_enc_0b_pin-pinname-enc0_i_pin--mc_enc_0i_pin-pinname-enc1_a_pin--mc_enc_1a_pin-pinname-enc1_b_pin--mc_enc_1b_pin-pinname-enc1_i_pin--mc_enc_1i_pin)`(PinName enc0_a_pin, PinName enc0_b_pin, PinName enc0_i_pin, PinName enc1_a_pin, PinName enc1_b_pin, PinName enc1_i_pin)` | Construct an EncoderClass object. +`public ` [`~EncoderClass`](#public-encoderclass)`()` | Destruct the EncoderClass object. +`public void` [`reset`](#public-void-resetint-channel)`(int channel)` | Reset the encoder counter for the specified channel. +`public int` [`getCurrentState`](#public-int-getcurrentstateint-channel)`(int channel)` | Get the current state of the specified encoder channel. +`public int` [`getPulses`](#public-int-getpulsesint-channel)`(int channel)` | Get the number of pulses counted by the specified encoder channel. +`public int` [`getRevolutions`](#public-int-getrevolutionsint-channel)`(int channel)` | Get the number of revolutions counted by the specified encoder channel. + +# class `ProgrammableDINClass` +Class for the Programmable Digital Input connector of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`ProgrammableDINClass`](#public-programmabledinclass)`()` | Construct a ProgrammableDINClass object. +`public ` [`~ProgrammableDINClass`](#public-programmabledinclass)`()` | Destruct the ProgrammableDINClass object. +`public bool` [`begin`](#public-bool-begin)`()` | Initialize the ProgrammableDIN module. + +# class `ProgrammableDIOClass` +Class for the Programmable Digital IO connector of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`ProgrammableDIOClass`](#public-programmabledioclasspinname-latch_pin--mc_pdio_latch_pin-pinname-latch_pin)`(PinName latch_pin)` | Construct a ProgrammableDIOClass object. +`public ` [`~ProgrammableDIOClass`](#public-programmabledioclass)`()` | Destruct the ProgrammableDIOClass object. +`public bool` [`begin`](#public-bool-beginbool-latch_mode--true)`(bool latch_mode)` | Initialize the ProgrammableDIO module with the specified latch mode. + +# class `RS485CommClass` +Class for managing the RS485 and RS232 communication protocols of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`RS485CommClass`](#public-rs485commclassarduino::uart--uart_itf-pinname-rs_tx_pin--mc_rs485_tx_pin-pinname-rs_de_pin--mc_rs485_de_pin-pinname-rs_re_pin--mc_rs485_re_pin)`(arduino::UART& uart_itf, PinName rs_tx_pin, PinName rs_de_pin, PinName rs_re_pin)` | Construct a RS485CommClass object. +`public ` [`~RS485CommClass`](#public-rs485commclass)`()` | Destruct the RS485CommClass object. +`public void` [`begin`](#public-void-beginunsigned-long-baudrate--115200-int-predelay--rs485_default_pre_delay-int-postdelay--rs485_default_post_delay)`(unsigned long baudrate, int predelay, int postdelay)` | Begin the RS485 communication protocol. +`public void` [`end`](#public-void-end)`()` | Close the RS485 communication protocol. +`public void` [`setModeRS232`](#public-void-setmoders232bool-enable)`(bool enable)` | Set RS485 mode to RS232. +`public void` [`setYZTerm`](#public-void-setyztermbool-enable)`(bool enable)` | Set YZ termination for RS485 communication. +`public void` [`setABTerm`](#public-void-setabtermbool-enable)`(bool enable)` | Set AB termination for RS485 communication. +`public void` [`setSlew`](#public-void-setslewbool-enable)`(bool enable)` | Set the slew rate for RS485 communication. +`public void` [`setFullDuplex`](#public-void-setfullduplexbool-enable)`(bool enable)` | Set RS485 communication to Full Duplex mode. + +# class `RTDTempProbeClass` +Class for managing RTD temperature sensor inputs of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`RTDTempProbeClass`](#public-rtdtempprobeclasspinname-rtd_cs_pin--mc_rtd_cs_pin-pinname-ch_sel0_pin--mc_rtd_sel0_pin-pinname-ch_sel1_pin--mc_rtd_sel1_pin-pinname-ch_sel2_pin--mc_rtd_sel2_pin-pinname-rtd_th_pin--mc_rtd_th_pin)`(PinName rtd_cs_pin, PinName ch_sel0_pin, PinName ch_sel1_pin, PinName ch_sel2_pin, PinName rtd_th_pin)` | Construct a RTDTempProbeClass object. +`public ` [`~RTDTempProbeClass`](#public-rtdtempprobeclass)`()` | Destruct the RTDTempProbeClass object. +`public bool` [`begin`](#public-bool-beginuint8_t-io_address--three_wire)`(uint8_t io_address)` | Initialize the RTDTempProbeClass with the specified I/O address. +`public void` [`end`](#public-void-end)`()` | Disable the temperature sensors and release any resources. +`public void` [`selectChannel`](#public-void-selectchannelint-channel)`(int channel)` | Select the input channel to be read (3 channels available). + +# class `RtcControllerClass` +Class for controlling the PCF8563T RTC. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`RtcControllerClass`](#public-rtccontrollerclasspinname-int_pin--mc_rtc_int_pin)`(PinName int_pin)` | Construct a RtcControllerClass object with an interrupt pin. +`public ` [`~RtcControllerClass`](#public-rtccontrollerclass)`()` | Destructor for the RtcControllerClass. + +# class `TCTempProbeClass` +Class for managing thermocouples temperature sensor of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`TCTempProbeClass`](#public-tctempprobeclasspinname-tc_cs_pin--mc_tc_cs_pin-pinname-ch_sel0_pin--mc_tc_sel0_pin-pinname-ch_sel1_pin--mc_tc_sel1_pin-pinname-ch_sel2_pin--mc_tc_sel2_pin)`(PinName tc_cs_pin, PinName ch_sel0_pin, PinName ch_sel1_pin, PinName ch_sel2_pin)` | Construct a TCTempProbeClass object. +`public ` [`~TCTempProbeClass`](#public-tctempprobeclass)`()` | Destruct the TCTempProbeClass object. +`public bool` [`begin`](#public-bool-begin)`()` | Initialize the TCTempProbeClass. +`public void` [`end`](#public-void-end)`()` | Disable the temperature sensors and release any resources. +`public void` [`selectChannel`](#public-void-selectchannelint-channel)`(int channel)` | Select the input channel to be read (3 channels available). + +# class `USBClass` +Class for managing the USB functionality of the Portenta Machine Control. + +## Summary + + Members | Descriptions +--------------------------------|--------------------------------------------- +`public ` [`USBClass`](#public-usbclasspinname-power_pin--mc_usb_pwr_pin-pinname-usbflag_pin--mc_usb_flag_pin)`(PinName power_pin, PinName usbflag_pin)` | Construct a USBClass object. +`public ` [`~USBClass`](#public-usbclass)`()` | Destruct the USBClass object. +`public bool` [`begin`](#public-bool-begin)`()` | Begin the USB functionality. +`public void` [`end`](#public-void-end)`()` | End the USB functionality. +`public bool` [`getFaultStatus`](#public-bool-getfaultstatus)`()` | Get the fault status of the USBA VBUS. From b70a4b4db61a0ed827edfc64f458439555db5476 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis <45899760+leonardocavagnis@users.noreply.github.com> Date: Thu, 17 Aug 2023 12:01:29 +0200 Subject: [PATCH 38/47] Update docs/README.md --- docs/README.md | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/docs/README.md b/docs/README.md index ac53a00..56c50af 100644 --- a/docs/README.md +++ b/docs/README.md @@ -31,12 +31,7 @@ https://www.arduino.cc/reference/en/libraries/arduino_machinecontrol - Supports various communication protocols: - CAN-BUS - Serial protocols (RS232/RS422/RS485) - -- Supports connectivity options: - - Ethernet - USB - - Bluetooth Low Energy - - Wi-Fi - Handles RTC (Real-Time Clock) functionality @@ -93,4 +88,4 @@ The API documentation can be found [here](./api.md). ## License -This library is released under the [LGPLv2.1 license](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt). \ No newline at end of file +This library is released under the [LGPLv2.1 license](https://github.com/arduino-libraries/Arduino_MachineControl/blob/master/LICENSE.txt). From dc6ae4369668f66d1a924d4b3100c0ad2e27867d Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis <45899760+leonardocavagnis@users.noreply.github.com> Date: Tue, 22 Aug 2023 16:12:44 +0200 Subject: [PATCH 39/47] Update keywords.txt --- keywords.txt | 57 +++++++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 47 insertions(+), 10 deletions(-) diff --git a/keywords.txt b/keywords.txt index 00f390c..4ac5d86 100644 --- a/keywords.txt +++ b/keywords.txt @@ -1,18 +1,55 @@ -####################################### -# Syntax Coloring Map For MachineControl -####################################### +################################################ +# Syntax Coloring Map For Arduino_MachineControl +################################################ # Class (KEYWORD1) -####################################### +################################################ -Arduino_MachineControl KEYWORD1 +Arduino_MachineControl KEYWORD1 -####################################### +MachineControl_AnalogIn KEYWORD1 +MachineControl_AnalogOut KEYWORD1 +MachineControl_CANComm KEYWORD1 +MachineControl_DigitalOutputs KEYWORD1 +MachineControl_Encoders KEYWORD1 +MachineControl_DigitalInputs KEYWORD1 +MachineControl_DigitalProgrammables KEYWORD1 +MachineControl_RS485Comm KEYWORD1 +MachineControl_RTDTempProbe KEYWORD1 +MachineControl_RTCController KEYWORD1 +MachineControl_TCTempProbe KEYWORD1 +MachineControl_USBController KEYWORD1 + +################################################ # Methods and Functions (KEYWORD2) -####################################### +################################################ begin KEYWORD2 -end KEYWORD2 +end KEYWORD2 + +read KEYWORD2 + +setPeriod KEYWORD2 +write KEYWORD2 + +available KEYWORD2 + +writeAll KEYWORD2 + +reset KEYWORD2 +getCurrentState KEYWORD2 +getPulses KEYWORD2 +getRevolutions KEYWORD2 + +setModeRS232 KEYWORD2 +setYZTerm KEYWORD2 +setABTerm KEYWORD2 +setSlew KEYWORD2 +setFullDuplex KEYWORD2 + +selectChannel KEYWORD2 + +getFaultStatus KEYWORD2 -####################################### +################################################ # Constants (LITERAL1) -####################################### +################################################ From 79028175613f45f0ff36142594c53b1e31471c41 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis <45899760+leonardocavagnis@users.noreply.github.com> Date: Tue, 22 Aug 2023 16:16:51 +0200 Subject: [PATCH 40/47] Update library.properties --- library.properties | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/library.properties b/library.properties index 4c23538..17803fb 100644 --- a/library.properties +++ b/library.properties @@ -2,8 +2,8 @@ name=Arduino_MachineControl version=1.1.1 author=Arduino maintainer=Arduino -sentence=Arduino Library for Portenta Machine Control - PMC -paragraph= +sentence=Arduino Library for Portenta Machine Control (PMC) +paragraph=The Portenta Machine Control Library is a C++ library designed to efficiently manage the functionalities of the Portenta Machine Control board. category=Communication url=https://github.com/arduino-libraries/Arduino_MachineControl architectures=mbed, mbed_portenta From e3edfa7a44540d2482cdb8d8d53e4bbeaf2a53cd Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 24 Aug 2023 16:04:54 +0200 Subject: [PATCH 41/47] AnalogIn: change sensor type management --- docs/api.md | 2 +- .../Analog_input_0_10V/Analog_input_0_10V.ino | 2 +- .../Analog_input_4_20mA.ino | 2 +- .../Analog_input_NTC/Analog_input_NTC.ino | 2 +- library.properties | 2 +- src/AnalogInClass.cpp | 8 ++++---- src/AnalogInClass.h | 20 +++++++++++-------- 7 files changed, 21 insertions(+), 17 deletions(-) diff --git a/docs/api.md b/docs/api.md index 48d98f6..40250fb 100644 --- a/docs/api.md +++ b/docs/api.md @@ -24,7 +24,7 @@ Class for the Analog IN connector of the Portenta Machine Control. --------------------------------|--------------------------------------------- `public ` [`AnalogInClass`](#public-analoginclasspinname-ai0_pin--mc_ai_ai0_pin-pinname-ai1_pin--mc_ai_ai1_pin-pinname-ai2_pin--mc_ai_ai2_pin)`(PinName ai0_pin, PinName ai1_pin, PinName ai2_pin)` | Construct an Analog Input reader for the Portenta Machine Control. `public ` [`~AnalogInClass`](#public-analoginclass)`()` | Destruct the AnalogInClass object. -`public bool` [`begin`](#public-bool-beginint-sensor_type-int-res_bits--16)`(int sensor_type, int res_bits)` | Initialize the analog reader, configure the sensor type and read resolution. +`public bool` [`begin`](#public-bool-beginint-sensor_type-int-res_bits--16)`(SensorType sensor_type, int res_bits)` | Initialize the analog reader, configure the sensor type and read resolution. `public uint16_t` [`read`](#public-uint16_t-readint-channel)`(int channel)` | Read the sampled voltage from the selected channel. # class `AnalogOutClass` diff --git a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino index 3573b44..944fe31 100644 --- a/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino +++ b/examples/Analog_input/Analog_input_0_10V/Analog_input_0_10V.ino @@ -25,7 +25,7 @@ void setup() { ; // wait for serial port to connect. } - MachineControl_AnalogIn.begin(MCAI_SENSOR_0_10V); + MachineControl_AnalogIn.begin(SensorType::V_0_10); } void loop() { diff --git a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino index 23f6d94..e952608 100644 --- a/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino +++ b/examples/Analog_input/Analog_input_4_20mA/Analog_input_4_20mA.ino @@ -26,7 +26,7 @@ void setup() { ; // wait for serial port to connect. } - MachineControl_AnalogIn.begin(MCAI_SENSOR_4_20MA); + MachineControl_AnalogIn.begin(SensorType::MA_4_20); } void loop() { diff --git a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino index 175771d..fbe5e02 100644 --- a/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino +++ b/examples/Analog_input/Analog_input_NTC/Analog_input_NTC.ino @@ -29,7 +29,7 @@ void setup() { ; // wait for serial port to connect. } - MachineControl_AnalogIn.begin(MCAI_SENSOR_NTC); + MachineControl_AnalogIn.begin(SensorType::NTC); } void loop() { diff --git a/library.properties b/library.properties index 17803fb..b083d68 100644 --- a/library.properties +++ b/library.properties @@ -8,4 +8,4 @@ category=Communication url=https://github.com/arduino-libraries/Arduino_MachineControl architectures=mbed, mbed_portenta includes=Arduino_MachineControl.h -depends=ArduinoRS485 +depends=ArduinoRS485, Arduino_CAN diff --git a/src/AnalogInClass.cpp b/src/AnalogInClass.cpp index 2bdba74..5d2478b 100644 --- a/src/AnalogInClass.cpp +++ b/src/AnalogInClass.cpp @@ -49,14 +49,14 @@ AnalogInClass::AnalogInClass(PinName ai0_pin, PinName ai1_pin, PinName ai2_pin) AnalogInClass::~AnalogInClass() { } -bool AnalogInClass::begin(int sensor_type, int res_bits) { +bool AnalogInClass::begin(SensorType sensor_type, int res_bits) { bool ret = true; /* Set bit resolution of ADC */ analogReadResolution(res_bits); switch (sensor_type) { - case MCAI_SENSOR_NTC: + case SensorType::NTC: /* Enable a 100K resistor in series with the reference voltage. * The voltage sampled is the voltage division between the 100k resistor and the input resistor (NTC/PTC) */ digitalWrite(CH0_IN1, LOW); @@ -74,7 +74,7 @@ bool AnalogInClass::begin(int sensor_type, int res_bits) { digitalWrite(CH2_IN3, HIGH); digitalWrite(CH2_IN4, HIGH); break; - case MCAI_SENSOR_0_10V: + case SensorType::V_0_10: /* Configure the input resistor dividers to have a ratio of 0.28 * (Maximum input voltage is 10V). */ digitalWrite(CH0_IN1, HIGH); @@ -92,7 +92,7 @@ bool AnalogInClass::begin(int sensor_type, int res_bits) { digitalWrite(CH2_IN3, LOW); digitalWrite(CH2_IN4, HIGH); break; - case MCAI_SENSOR_4_20MA: + case SensorType::MA_4_20: /* Enable a 120 ohm resistor to GND to convert the 4-20mA sensor currents to voltage. * Note: 24V are available from the carrier to power the 4-20mA sensors. */ digitalWrite(CH0_IN1, HIGH); diff --git a/src/AnalogInClass.h b/src/AnalogInClass.h index 3b0421f..1b542ab 100644 --- a/src/AnalogInClass.h +++ b/src/AnalogInClass.h @@ -17,11 +17,15 @@ /* Exported defines ----------------------------------------------------------*/ -/** Analog Sensor type **/ -#define MCAI_SENSOR_NTC 1 -#define MCAI_SENSOR_0_10V 2 -#define MCAI_SENSOR_4_20MA 3 - +/** + * @brief Enum class that represents different sensor types. + */ +enum class SensorType { + NTC = 1, + V_0_10 = 2, + MA_4_20 = 3 +}; + /* Class ----------------------------------------------------------------------*/ /** @@ -49,11 +53,11 @@ class AnalogInClass { /** * @brief Initialize the analog reader, configure the sensor type and read resolution. * - * @param sensor_type The sensor type (0-10V, 4-20mA or NTC) + * @param sensor_type The sensor type (NTC, V_0_10 or MA_4_20) * @param res_bits Resolution in bits of the read analog value - * @return true If the analog reader is successfully initialized, false Otherwise + * @return true If the analog reader is successfully initialized, false otherwise */ - bool begin(int sensor_type, int res_bits = 16); + bool begin(SensorType sensor_type, int res_bits = 16); /** * @brief Read the sampled voltage from the selected channel. From c0bafb89d0cbd40579a5729860fda6a88a70e659 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 20 Sep 2023 16:01:52 +0200 Subject: [PATCH 42/47] removing PT1000 example, not compatible --- examples/Temp_probes_RTD/Temp_probes_RTD.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Temp_probes_RTD/Temp_probes_RTD.ino b/examples/Temp_probes_RTD/Temp_probes_RTD.ino index 7961d30..9967b30 100644 --- a/examples/Temp_probes_RTD/Temp_probes_RTD.ino +++ b/examples/Temp_probes_RTD/Temp_probes_RTD.ino @@ -17,10 +17,10 @@ #include -// The value of the Rref resistor. Use 430.0 for PT100 and 4300.0 for PT1000 +// The value of the Rref resistor. Use 430.0 for PT100 #define RREF 400.0 // The 'nominal' 0-degrees-C resistance of the sensor -// 100.0 for PT100, 1000.0 for PT1000 +// 100.0 for PT100 #define RNOMINAL 100.0 void setup() { From d4180487d2155d8a0e35f27ae5b9ae421733c655 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Thu, 21 Sep 2023 14:54:42 +0200 Subject: [PATCH 43/47] fix mispelling of RTC methods --- examples/RTC/RTC.ino | 18 +++++++++--------- src/utility/RTC/PCF8563T.cpp | 30 +++++++++++++++--------------- src/utility/RTC/PCF8563T.h | 12 ++++++------ 3 files changed, 30 insertions(+), 30 deletions(-) diff --git a/examples/RTC/RTC.ino b/examples/RTC/RTC.ino index 87eba27..a12b800 100644 --- a/examples/RTC/RTC.ino +++ b/examples/RTC/RTC.ino @@ -13,9 +13,9 @@ #include -int years = 20; -int months = 9; -int days = 24; +int year = 20; +int month = 9; +int day = 24; int hours = 12; int minutes = 43; int seconds = 31; @@ -36,9 +36,9 @@ void setup() { // The RTC time can be set as epoch, using one of the following two options: // - Calendar time: MachineControl_RTCController.setEpoch(years, months, days, hours, minutes, seconds); // - UTC time: MachineControl_RTCController.setEpoch(date_in_seconds); - MachineControl_RTCController.setYears(years); - MachineControl_RTCController.setMonths(months); - MachineControl_RTCController.setDays(days); + MachineControl_RTCController.setYear(year); + MachineControl_RTCController.setMonth(month); + MachineControl_RTCController.setDay(day); MachineControl_RTCController.setHours(hours); MachineControl_RTCController.setMinutes(minutes); MachineControl_RTCController.setSeconds(seconds); @@ -48,11 +48,11 @@ void setup() { void loop() { // APIs to get date's fields Serial.print("Date: "); - Serial.print(MachineControl_RTCController.getYears()); + Serial.print(MachineControl_RTCController.getYear()); Serial.print("/"); - Serial.print(MachineControl_RTCController.getMonths()); + Serial.print(MachineControl_RTCController.getMonth()); Serial.print("/"); - Serial.print(MachineControl_RTCController.getDays()); + Serial.print(MachineControl_RTCController.getDay()); Serial.print(" - "); Serial.print(MachineControl_RTCController.getHours()); Serial.print(":"); diff --git a/src/utility/RTC/PCF8563T.cpp b/src/utility/RTC/PCF8563T.cpp index 6d0176f..b2ef09b 100644 --- a/src/utility/RTC/PCF8563T.cpp +++ b/src/utility/RTC/PCF8563T.cpp @@ -79,7 +79,7 @@ bool PCF8563TClass::begin() * Save an unsigned byte with the Year's value * @param years Year's unsigned byte */ -void PCF8563TClass::setYears(uint8_t years) { +void PCF8563TClass::setYear(uint8_t years) { uint8_t dec = years / 10; uint8_t unit = years - (dec * 10); writeByte(PCF8563T_YEARS_REG, ((dec << 4) + unit)); @@ -90,7 +90,7 @@ void PCF8563TClass::setYears(uint8_t years) { * Save an unsigned byte with the Month's value * @param months Month's unsigned byte (0 to 12) */ -void PCF8563TClass::setMonths(uint8_t months) { +void PCF8563TClass::setMonth(uint8_t months) { uint8_t offset = 0; if (months > 9) { offset = 6; @@ -103,7 +103,7 @@ void PCF8563TClass::setMonths(uint8_t months) { * Save an unsigned byte with the Day's value * @param days day's unsigned byte */ -void PCF8563TClass::setDays(uint8_t days) { +void PCF8563TClass::setDay(uint8_t days) { uint8_t dec = days / 10; uint8_t unit = days - (dec * 10); writeByte(PCF8563T_DAYS_REG, ((dec << 4) + unit)); @@ -147,7 +147,7 @@ void PCF8563TClass::setSeconds(uint8_t seconds) { * Get unsigned byte with the Year(s) value * @return byte with Year(s) value */ -uint8_t PCF8563TClass::getYears() { +uint8_t PCF8563TClass::getYear() { uint8_t years = readByte(PCF8563T_YEARS_REG); return (years & 0x0F) + ((years >> 4)*10); } @@ -157,7 +157,7 @@ uint8_t PCF8563TClass::getYears() { * Get unsigned byte with the month(s) value * @return byte with Month(s) value */ -uint8_t PCF8563TClass::getMonths() { +uint8_t PCF8563TClass::getMonth() { uint8_t months = readByte(PCF8563T_MONTHS_REG) & 0x1F; if(months > 9) { return months - 6; @@ -171,7 +171,7 @@ uint8_t PCF8563TClass::getMonths() { * Get unsigned byte with the Day(s) value * @return byte with Day(s) value */ -uint8_t PCF8563TClass::getDays() { +uint8_t PCF8563TClass::getDay() { uint8_t days = readByte(PCF8563T_DAYS_REG) & 0x3F; return (days & 0x0F) + ((days >> 4)*10); } @@ -215,9 +215,9 @@ void PCF8563TClass::setEpoch() { time.tm_sec = getSeconds(); time.tm_min = getMinutes(); time.tm_hour = getHours(); - time.tm_mday = getDays(); - time.tm_mon = getMonths() - 1; - time.tm_year = getYears() + 100; + time.tm_mday = getDay(); + time.tm_mon = getMonth() - 1; + time.tm_year = getYear() + 100; time_t seconds; _rtc_maketime(&time, &seconds, RTC_FULL_LEAP_YEAR_SUPPORT); set_time(seconds); @@ -236,9 +236,9 @@ void PCF8563TClass::setEpoch(time_t seconds) { setSeconds(time.tm_sec); setMinutes(time.tm_min); setHours( time.tm_hour); - setDays(time.tm_mday); - setMonths(time.tm_mon + 1); - setYears((time.tm_year - 100)); + setDay(time.tm_mday); + setMonth(time.tm_mon + 1); + setYear((time.tm_year - 100)); set_time(seconds); } @@ -286,9 +286,9 @@ time_t PCF8563TClass::getEpoch() { time.tm_sec = getSeconds(); time.tm_min = getMinutes(); time.tm_hour = getHours(); - time.tm_mday = getDays(); - time.tm_mon = getMonths() - 1; - time.tm_year = getYears() + 100; // year since 1900 + time.tm_mday = getDay(); + time.tm_mon = getMonth() - 1; + time.tm_year = getYear() + 100; // year since 1900 _rtc_maketime(&time, &seconds, RTC_FULL_LEAP_YEAR_SUPPORT); return seconds; diff --git a/src/utility/RTC/PCF8563T.h b/src/utility/RTC/PCF8563T.h index c854ef9..12786cb 100644 --- a/src/utility/RTC/PCF8563T.h +++ b/src/utility/RTC/PCF8563T.h @@ -31,16 +31,16 @@ class PCF8563TClass { public: PCF8563TClass(); bool begin(); - void setYears(uint8_t years); - void setMonths(uint8_t months); - void setDays(uint8_t days); + void setYear(uint8_t years); + void setMonth(uint8_t months); + void setDay(uint8_t days); void setHours(uint8_t hours); void setMinutes(uint8_t minutes); void setSeconds(uint8_t seconds); - uint8_t getYears(); - uint8_t getMonths(); - uint8_t getDays(); + uint8_t getYear(); + uint8_t getMonth(); + uint8_t getDay(); uint8_t getHours(); uint8_t getMinutes(); uint8_t getSeconds(); From 00c84045791650c8ef6b53e660d3f7a80c34a0cd Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Fri, 17 Nov 2023 11:58:01 +0100 Subject: [PATCH 44/47] move PinDefinitions inclusion in cpp to avoid compilation issue --- src/CANCommClass.cpp | 1 + src/CANCommClass.h | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/src/CANCommClass.cpp b/src/CANCommClass.cpp index f179e77..33e04c8 100644 --- a/src/CANCommClass.cpp +++ b/src/CANCommClass.cpp @@ -6,6 +6,7 @@ /* Includes -----------------------------------------------------------------*/ #include "CANCommClass.h" +#include /* Functions -----------------------------------------------------------------*/ CANCommClass::CANCommClass(PinName can_tx_pin, PinName can_rx_pin, PinName can_stb_pin) : diff --git a/src/CANCommClass.h b/src/CANCommClass.h index 78afeda..52d1ae9 100644 --- a/src/CANCommClass.h +++ b/src/CANCommClass.h @@ -12,7 +12,6 @@ /* Includes -------------------------------------------------------------------*/ #include -#include #include #include #include "pins_mc.h" From 65c748c2f514d09bf20f311adc70c8d62f8d9eb6 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Tue, 28 Nov 2023 17:15:31 +0100 Subject: [PATCH 45/47] add fast analog input read example using Arduino_AdvancedAnalog library --- .../Fast_Analog_input_0_10V.ino | 108 ++++++++++++++++++ 1 file changed, 108 insertions(+) create mode 100644 examples/Analog_input/Fast_Analog_input_0_10V/Fast_Analog_input_0_10V.ino diff --git a/examples/Analog_input/Fast_Analog_input_0_10V/Fast_Analog_input_0_10V.ino b/examples/Analog_input/Fast_Analog_input_0_10V/Fast_Analog_input_0_10V.ino new file mode 100644 index 0000000..734c370 --- /dev/null +++ b/examples/Analog_input/Fast_Analog_input_0_10V/Fast_Analog_input_0_10V.ino @@ -0,0 +1,108 @@ +/* + * Portenta Machine Control - Fast Analog In 0-10 V + * + * This example provides the voltage value acquired by the Machine Control using the Arduino_AdvancedAnalog library, + * which is designed to offer enhanced performance in terms of acquisition speed compared to the MachineControl_AnalogIn feature. + * For each channel of the ANALOG IN connector, there is a resistor divider made by a 100k and 39k; the input voltage is divided by a ratio of 0.28. + * The maximum input voltage is 10V. + * To use the 0V-10V functionality, a 24V supply on the PWR SUPPLY connector is necessary. + * + * The circuit: + * - Portenta H7 + * - Portenta Machine Control + * + * Initial author: Leonardo Cavagnis @leonardocavagnis + */ + +#include +#include + +const float RES_DIVIDER = 0.28057; +const float REFERENCE = 3.0; + +//A3 is connected to PMC-AI0, A2 is connected to PMC-AI1 +AdvancedADC MachineControl_FastAnalogIn01(A3, A2); //A3 & A2 share the same ADC instance (ADC3) +//A1 is connected to PMC-AI2 +AdvancedADC MachineControl_FastAnalogIn2(A1); + +uint16_t adc_get_buf(AdvancedADC &adc); +void adc_get_buf(AdvancedADC &adc, uint16_t * sample_buf, uint8_t sample_buf_size); + +void setup() { + Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. + } + + // Configure the sensor type 0-10V + MachineControl_AnalogIn.begin(SensorType::V_0_10); + + // Initialize the Advanced Analog feature on PMC AI pins + if (!MachineControl_FastAnalogIn01.begin(AN_RESOLUTION_16, 8000, 32, 3)) { + Serial.println("AI0, AI1: Failed to start analog acquisition!"); + while (1); + } + + if (!MachineControl_FastAnalogIn2.begin(AN_RESOLUTION_16, 8000, 32, 3)) { + Serial.println("AI2: Failed to start analog acquisition!"); + while (1); + } +} + +void loop() { + uint16_t raw_voltage_ch01[2] = {0, 0}; + uint16_t raw_voltage_ch2 = 0; + + adc_get_buf(MachineControl_FastAnalogIn01, raw_voltage_ch01, 2); + float voltage_ch0 = ((float)raw_voltage_ch01[0] * REFERENCE) / 65535 / RES_DIVIDER; + Serial.print("Voltage CH0: "); + Serial.print(voltage_ch0, 3); + Serial.println("V"); + + float voltage_ch1 = ((float)raw_voltage_ch01[1] * REFERENCE) / 65535 / RES_DIVIDER; + Serial.print("Voltage CH1: "); + Serial.print(voltage_ch1, 3); + Serial.println("V"); + + raw_voltage_ch2 = adc_get_buf(MachineControl_FastAnalogIn2); + float voltage_ch2 = ((float)raw_voltage_ch2 * REFERENCE) / 65535 / RES_DIVIDER; + Serial.print("Voltage CH2: "); + Serial.print(voltage_ch2, 3); + Serial.println("V"); + + Serial.println(); + delay(250); +} + +uint16_t adc_get_buf(AdvancedADC &adc) { + uint16_t sample = 0; + + if (adc.available()) { + SampleBuffer buf = adc.read(); + + // Print first sample. + sample = buf[0]; + Serial.println(sample); + + // Release the buffer to return it to the pool. + buf.release(); + } + + return sample; +} + +void adc_get_buf(AdvancedADC &adc, uint16_t * sample_buf, uint8_t sample_buf_size) { + if (adc.available()) { + SampleBuffer buf = adc.read(); + + for (uint8_t pos = 0; pos < sample_buf_size; pos++) { + sample_buf[pos] = buf[pos]; + Serial.println(sample_buf[pos]); + } + + // Release the buffer to return it to the pool. + buf.release(); + } + + return; +} \ No newline at end of file From 5edf8d897dd7f543a973a285d9c5382d4c6cd9ad Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis <45899760+leonardocavagnis@users.noreply.github.com> Date: Mon, 11 Dec 2023 10:57:09 +0100 Subject: [PATCH 46/47] Update compile-examples.yml --- .github/workflows/compile-examples.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/compile-examples.yml b/.github/workflows/compile-examples.yml index 38999da..39fd50f 100644 --- a/.github/workflows/compile-examples.yml +++ b/.github/workflows/compile-examples.yml @@ -45,6 +45,7 @@ jobs: libraries: | - source-path: ./ - name: ArduinoRS485 + - name: Arduino_AdvancedAnalog sketch-paths: | - examples enable-deltas-report: true From bbb3fe0b4d498705bad84a3c5e542d908ad3c231 Mon Sep 17 00:00:00 2001 From: Leonardo Cavagnis Date: Wed, 10 Jan 2024 15:50:26 +0100 Subject: [PATCH 47/47] fix Thermocouple readings --- src/utility/THERMOCOUPLE/MAX31855.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/utility/THERMOCOUPLE/MAX31855.h b/src/utility/THERMOCOUPLE/MAX31855.h index 389e5b4..4334c3c 100644 --- a/src/utility/THERMOCOUPLE/MAX31855.h +++ b/src/utility/THERMOCOUPLE/MAX31855.h @@ -41,7 +41,7 @@ class MAX31855Class { private: uint32_t readSensor(); float _coldOffset; - int _cs; + PinName _cs; SPIClass* _spi; SPISettings _spiSettings;