diff --git a/README.md b/README.md
index fe932a5..0b21f22 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
## grblHAL ##
-Latest build date is 20250405, see the [changelog](changelog.md) for details.
+Latest build date is 20250413, see the [changelog](changelog.md) for details.
> [!NOTE]
> A settings reset will be performed on an update of builds prior to 20241208. Backup and restore of settings is recommended.
@@ -89,4 +89,4 @@ G/M-codes not supported by [legacy Grbl](https://github.com/gnea/grbl/wiki) are
Some [plugins](https://github.com/grblHAL/plugins) implements additional M-codes.
---
-20250328
+20250413
diff --git a/changelog.md b/changelog.md
index 0476fc9..4017566 100644
--- a/changelog.md
+++ b/changelog.md
@@ -1,5 +1,26 @@
## grblHAL changelog
+20250413
+
+Core:
+
+* For developers: added wrappers/veneers for `hal.port` functions, plugin code should be changed to use these instead of calling via `hal.port` functions or accessing `hal.port` properties.
+Improved the [ioports API](https://svn.io-engineering.com/grblHAL/html/ioports_8c.html), updated core code to make use of it. Flagged some calls and (part of) some stuctures as deprecated.
+
+Drivers:
+
+* Most: updated to make use of the new ioports API functionality.
+
+* Some: removed references to deleted odometer include. Ref. odometer issue [#2](https://github.com/grblHAL/Plugin_odometer/issues/2).
+
+Plugins:
+
+* Fans: fixed bug preventing selection of ports to use. Possibly related to issue [#242 comment](https://github.com/grblHAL/core/issues/242#issuecomment-2798816316).
+
+* Many: updated to make use of the new ioports API functionality.
+
+---
+
20250411
Core:
diff --git a/crossbar.h b/crossbar.h
index a2d4d12..b051486 100644
--- a/crossbar.h
+++ b/crossbar.h
@@ -58,17 +58,20 @@ typedef enum {
Input_MPGSelect,
Input_ModeSelect = Input_MPGSelect, // Deprecated
Input_LimitX,
- Input_LimitX_2,
+ Input_LimitX2,
+ Input_LimitX_2 = Input_LimitX2, // Deprecated
Input_LimitX_Max,
Input_HomeX,
Input_HomeX_2,
Input_LimitY,
- Input_LimitY_2,
+ Input_LimitY2,
+ Input_LimitY_2 = Input_LimitY2, // Deprecated
Input_LimitY_Max,
Input_HomeY,
Input_HomeY_2,
Input_LimitZ,
- Input_LimitZ_2,
+ Input_LimitZ2,
+ Input_LimitZ_2 = Input_LimitZ2, // Deprecated
Input_LimitZ_Max,
Input_HomeZ,
Input_HomeZ_2,
@@ -126,22 +129,28 @@ typedef enum {
// Output pins
Output_StepX,
Outputs = Output_StepX,
- Output_StepX_2,
+ Output_StepX2,
+ Output_StepX_2 = Output_StepX2, // deprecated
Output_StepY,
- Output_StepY_2,
+ Output_StepY2,
+ Output_StepY_2 = Output_StepY2, // deprecated
Output_StepZ,
- Output_StepZ_2,
+ Output_StepZ2,
+ Output_StepZ_2 = Output_StepZ2, // deprecated
Output_StepA,
Output_StepB,
Output_StepC,
Output_StepU,
Output_StepV,
Output_DirX,
- Output_DirX_2,
+ Output_DirX2,
+ Output_DirX_2 = Output_DirX2, // deprecated
Output_DirY,
- Output_DirY_2,
+ Output_DirY2,
+ Output_DirY_2 = Output_DirY2, // deprecated
Output_DirZ,
- Output_DirZ_2,
+ Output_DirZ2,
+ Output_DirZ_2 = Output_DirZ2, // deprecated
Output_DirA,
Output_DirB,
Output_DirC,
@@ -158,9 +167,13 @@ typedef enum {
Output_MotorChipSelectM7,
Output_StepperPower,
Output_StepperEnable,
+ Output_StepperEnableSTEPPERS = Output_StepperEnable,
Output_StepperEnableX,
+ Output_StepperEnableX2 = Output_StepperEnableX,
Output_StepperEnableY,
+ Output_StepperEnableY2 = Output_StepperEnableY,
Output_StepperEnableZ,
+ Output_StepperEnableZ2 = Output_StepperEnableZ,
Output_StepperEnableA,
Output_StepperEnableB,
Output_StepperEnableU,
@@ -342,17 +355,17 @@ PROGMEM static const pin_name_t pin_names[] = {
{ .function = Input_Analog_Aux7, .name = "Aux analog in 7" },
#endif
{ .function = Output_StepX, .name = "X step" },
- { .function = Output_StepX_2, .name = "X2 step" },
+ { .function = Output_StepX2, .name = "X2 step" },
{ .function = Output_StepY, .name = "Y step" },
- { .function = Output_StepY_2, .name = "Y2 step" },
+ { .function = Output_StepY2, .name = "Y2 step" },
{ .function = Output_StepZ, .name = "Z step" },
- { .function = Output_StepZ_2, .name = "Z2 step" },
+ { .function = Output_StepZ2, .name = "Z2 step" },
{ .function = Output_DirX, .name = "X dir" },
- { .function = Output_DirX_2, .name = "X2 dir" },
+ { .function = Output_DirX2, .name = "X2 dir" },
{ .function = Output_DirY, .name = "Y dir" },
- { .function = Output_DirY_2, .name = "Y2 dir" },
+ { .function = Output_DirY2, .name = "Y2 dir" },
{ .function = Output_DirZ, .name = "Z dir" },
- { .function = Output_DirZ_2, .name = "Z2 dir" },
+ { .function = Output_DirZ2, .name = "Z2 dir" },
{ .function = Output_StepperPower, .name = "Stepper power" },
{ .function = Output_StepperEnable, .name = "Steppers enable" },
{ .function = Output_StepperEnableX, .name = "X enable" },
@@ -726,6 +739,7 @@ typedef struct {
} aux_ctrl_out_t;
typedef struct xbar {
+ void *ports_id;
uint8_t id; //!< Pin id.
pin_function_t function; //!< Pin function.
pin_group_t group; //!< Pin group.
diff --git a/driver_opts2.h b/driver_opts2.h
index 34a789a..e4b6228 100644
--- a/driver_opts2.h
+++ b/driver_opts2.h
@@ -61,6 +61,124 @@
#define FLASH_ENABLE 0
#endif
+// Expand port shorthand names
+
+#ifdef ENABLE_PORT
+#ifdef STEPPERS_ENABLE_PIN
+#ifndef STEPPERS_ENABLE_PORT
+#define STEPPERS_ENABLE_PORT ENABLE_PORT
+#endif
+#else
+#ifdef XY_ENABLE_PIN
+#ifndef XY_ENABLE_PORT
+#define XY_ENABLE_PORT ENABLE_PORT
+#endif
+#else
+#ifndef X_ENABLE_PORT
+#define X_ENABLE_PORT ENABLE_PORT
+#endif
+#ifndef Y_ENABLE_PORT
+#define Y_ENABLE_PORT ENABLE_PORT
+#endif
+#endif
+#ifndef Z_ENABLE_PORT
+#define Z_ENABLE_PORT ENABLE_PORT
+#endif
+#if defined(M3_ENABLE_PIN) && !defined(M3_ENABLE_PORT)
+#define M3_ENABLE_PORT ENABLE_PORT
+#endif
+#if defined(M4_ENABLE_PIN) && !defined(M4_ENABLE_PORT)
+#define M4_ENABLE_PORT ENABLE_PORT
+#endif
+#if defined(M5_ENABLE_PIN) && !defined(M5_ENABLE_PORT)
+#define M5_ENABLE_PORT ENABLE_PORT
+#endif
+#if defined(M6_ENABLE_PIN) && !defined(M6_ENABLE_PORT)
+#define M6_ENABLE_PORT ENABLE_PORT
+#endif
+#if defined(M7_ENABLE_PIN) && !defined(M7_ENABLE_PORT)
+#define M7_ENABLE_PORT ENABLE_PORT
+#endif
+#endif
+#endif // ENABLE_PORT
+
+#ifdef STEP_PORT
+#ifndef X_STEP_PORT
+#define X_STEP_PORT STEP_PORT
+#endif
+#ifndef Y_STEP_PORT
+#define Y_STEP_PORT STEP_PORT
+#endif
+#ifndef Z_STEP_PORT
+#define Z_STEP_PORT STEP_PORT
+#endif
+#if defined(M3_STEP_PIN) && !defined(M3_STEP_PORT)
+#define M3_STEP_PORT STEP_PORT
+#endif
+#if defined(M4_STEP_PIN) && !defined(M4_STEP_PORT)
+#define M4_STEP_PORT STEP_PORT
+#endif
+#if defined(M5_STEP_PIN) && !defined(M5_STEP_PORT)
+#define M5_STEP_PORT STEP_PORT
+#endif
+#if defined(M6_STEP_PIN) && !defined(M6_STEP_PORT)
+#define M6_STEP_PORT STEP_PORT
+#endif
+#if defined(M7_STEP_PIN) && !defined(M7_STEP_PORT)
+#define M7_STEP_PORT STEP_PORT
+#endif
+#endif // STEP_PORT
+
+#ifdef DIRECTION_PORT
+#ifndef X_DIRECTION_PORT
+#define X_DIRECTION_PORT DIRECTION_PORT
+#endif
+#ifndef Y_DIRECTION_PORT
+#define Y_DIRECTION_PORT DIRECTION_PORT
+#endif
+#ifndef Z_DIRECTION_PORT
+#define Z_DIRECTION_PORT DIRECTION_PORT
+#endif
+#if defined(M3_DIRECTION_PIN) && !defined(M3_DIRECTION_PORT)
+#define M3_DIRECTION_PORT DIRECTION_PORT
+#endif
+#if defined(M4_DIRECTION_PIN) && !defined(M4_DIRECTION_PORT)
+#define M4_DIRECTION_PORT DIRECTION_PORT
+#endif
+#if defined(M5_DIRECTION_PIN) && !defined(M5_DIRECTION_PORT)
+#define M5_DIRECTION_PORT DIRECTION_PORT
+#endif
+#if defined(M6_DIRECTION_PIN) && !defined(M6_DIRECTION_PORT)
+#define M6_DIRECTION_PORT DIRECTION_PORT
+#endif
+#if defined(M7_DIRECTION_PIN) && !defined(M7_DIRECTION_PORT)
+#define M7_DIRECTION_PORT DIRECTION_PORT
+#endif
+#endif // DIRECTION_PORT
+
+#ifdef SPINDLE_PORT
+#ifndef SPINDLE_ENABLE_PORT
+#define SPINDLE_ENABLE_PORT SPINDLE_PORT
+#endif
+#if defined(SPINDLE_PWM_PIN) && !defined(SPINDLE_PWM_PORT)
+#define SPINDLE_PWM_PORT SPINDLE_PORT
+#endif
+#if defined(SPINDLE_DIRECTION_PIN) && !defined(SPINDLE_DIRECTION_PORT)
+#define SPINDLE_DIRECTION_PORT SPINDLE_PORT
+#endif
+#endif // SPINDLE_PORT
+
+#ifdef COOLANT_PORT
+#if defined(COOLANT_FLOOD_PIN) && !defined(COOLANT_FLOOD_PORT)
+#define COOLANT_FLOOD_PORT COOLANT_PORT
+#endif
+#if defined(COOLANT_MIST_PIN) && !defined(COOLANT_MIST_PORT)
+#define COOLANT_MIST_PORT COOLANT_PORT
+#endif
+#endif // COOLANT_PORT
+
+// End expand port shorthand names
+
#if TRINAMIC_ENABLE
#include "motors/trinamic.h"
diff --git a/expanders_init.h b/expanders_init.h
index 8564395..364a475 100644
--- a/expanders_init.h
+++ b/expanders_init.h
@@ -27,6 +27,8 @@
#pragma once
+extern void board_ports_init (void); // default is a weak function
+
// I2C expanders
#if PCA9654E_ENABLE || MCP3221_ENABLE || MCP4725_ENABLE
@@ -73,6 +75,8 @@ extern void pca9654e_init(void);
static inline void io_expanders_init (void)
{
+ board_ports_init(); // can be implemented by board specific code
+
#if MCP3221_ENABLE
mcp3221_init();
#endif
diff --git a/gcode.c b/gcode.c
index e5261fa..52b6980 100644
--- a/gcode.c
+++ b/gcode.c
@@ -1383,15 +1383,15 @@ status_code_t gc_execute_block (char *block)
case 63:
case 64:
case 65:
- if(hal.port.digital_out == NULL || ioports_unclaimed(Port_Digital, Port_Output) == 0)
+ if(!ioports_can_do().digital_out || ioports_unclaimed(Port_Digital, Port_Output) == 0)
FAIL(Status_GcodeUnsupportedCommand); // [Unsupported M command]
word_bit.modal_group.M5 = On;
port_command = (io_mcode_t)int_value;
break;
case 66:
- if(hal.port.wait_on_input == NULL || (ioports_unclaimed(Port_Digital, Port_Input) == 0 &&
- ioports_unclaimed(Port_Analog, Port_Input) == 0))
+ if(!ioports_can_do().wait_on_input || (ioports_unclaimed(Port_Digital, Port_Input) == 0 &&
+ ioports_unclaimed(Port_Analog, Port_Input) == 0))
FAIL(Status_GcodeUnsupportedCommand); // [Unsupported M command]
word_bit.modal_group.M5 = On;
port_command = (io_mcode_t)int_value;
@@ -1399,7 +1399,7 @@ status_code_t gc_execute_block (char *block)
case 67:
case 68:
- if(hal.port.analog_out == NULL || ioports_unclaimed(Port_Analog, Port_Output) == 0)
+ if(!ioports_can_do().analog_out || ioports_unclaimed(Port_Analog, Port_Output) == 0)
FAIL(Status_GcodeUnsupportedCommand); // [Unsupported M command]
word_bit.modal_group.M5 = On;
port_command = (io_mcode_t)int_value;
@@ -3307,11 +3307,11 @@ status_code_t gc_execute_block (char *block)
case IoMCode_OutputOnImmediate:
case IoMCode_OutputOffImmediate:
- hal.port.digital_out(gc_block.output_command.port, gc_block.output_command.value != 0.0f);
+ ioport_digital_out(gc_block.output_command.port, gc_block.output_command.value != 0.0f);
break;
case IoMCode_WaitOnInput:
- sys.var5399 = hal.port.wait_on_input((io_port_type_t)gc_block.output_command.is_digital, gc_block.output_command.port, (wait_mode_t)gc_block.values.l, gc_block.values.q);
+ sys.var5399 = ioport_wait_on_input((io_port_type_t)gc_block.output_command.is_digital, gc_block.output_command.port, (wait_mode_t)gc_block.values.l, gc_block.values.q);
system_add_rt_report(Report_M66Result);
break;
@@ -3320,7 +3320,7 @@ status_code_t gc_execute_block (char *block)
break;
case IoMCode_AnalogOutImmediate:
- hal.port.analog_out(gc_block.output_command.port, gc_block.output_command.value);
+ ioport_analog_out(gc_block.output_command.port, gc_block.output_command.value);
break;
}
}
diff --git a/grbl.h b/grbl.h
index 07b3a8a..3d4af67 100644
--- a/grbl.h
+++ b/grbl.h
@@ -42,7 +42,7 @@
#else
#define GRBL_VERSION "1.1f"
#endif
-#define GRBL_BUILD 20250409
+#define GRBL_BUILD 20250413
#define GRBL_URL "https://github.com/grblHAL"
diff --git a/grbllib.c b/grbllib.c
index 8581cd9..8c8c7dc 100644
--- a/grbllib.c
+++ b/grbllib.c
@@ -100,6 +100,11 @@ static settings_changed_ptr hal_settings_changed;
kinematics_t kinematics;
#endif
+__attribute__((weak)) void board_ports_init (void)
+{
+ // NOOP
+}
+
void dummy_bool_handler (bool arg)
{
// NOOP
diff --git a/ioports.c b/ioports.c
index ef95394..f976242 100644
--- a/ioports.c
+++ b/ioports.c
@@ -59,11 +59,6 @@ typedef struct {
ioport_bus_t bus;
} io_ports_private_t;
-typedef struct {
- uint8_t n_start;
- uint8_t n_end;
-} io_ports_range_t;
-
typedef struct {
digital_out_ptr digital_out; //!< Optional handler for setting a digital output.
analog_out_ptr analog_out; //!< Optional handler for setting an analog output.
@@ -75,8 +70,9 @@ typedef struct {
} ll_io_port_t;
typedef struct io_ports_list_t {
+ io_port_type_t type;
ll_io_port_t hal;
- io_ports_range_t port[4];
+ io_ports_data_t *ports_id;
struct io_ports_list_t *next;
} io_ports_list_t;
@@ -205,7 +201,7 @@ static bool match_port (xbar_t *properties, uint8_t port, void *data)
/*! \brief find first free or claimed digital or analog port.
\param type as an \a #io_port_type_t enum value.
\param dir as an \a #io_port_direction_t enum value.
-\param description pointer to a \a char constant for the pin description of a previousely claimed port or NULL if searching for the first free port.
+\param description pointer to a \a char constant for the pin description of a previousely claimed port or \a NULL if searching for the first free port.
\returns the port number if successful, 0xFF (255) if not.
*/
uint8_t ioport_find_free (io_port_type_t type, io_port_direction_t dir, pin_cap_t filter, const char *description)
@@ -226,7 +222,7 @@ uint8_t ioport_find_free (io_port_type_t type, io_port_direction_t dir, pin_cap_
\param type as an \a #io_port_type_t enum value.
\param dir as an \a #io_port_direction_t enum value.
\param port the port aux number.
-\returns pointer to \a xbar_t struct if successful, NULL if not.
+\returns pointer to \a xbar_t struct if successful, \a NULL if not.
*/
static xbar_t *get_info (io_port_type_t type, io_port_direction_t dir, uint8_t port, bool claim)
{
@@ -246,7 +242,7 @@ static xbar_t *get_info (io_port_type_t type, io_port_direction_t dir, uint8_t p
\param type as an \a #io_port_type_t enum value.
\param dir as an \a #io_port_direction_t enum value.
\param port the port aux number.
-\returns pointer to \a xbar_t struct if successful, NULL if not.
+\returns pointer to \a xbar_t struct if successful, \a NULL if not.
*/
xbar_t *ioport_get_info (io_port_type_t type, io_port_direction_t dir, uint8_t port)
{
@@ -283,36 +279,33 @@ static inline void dec_hcount (io_port_type_t type, io_port_direction_t dir)
\param dir as an \a #io_port_direction_t enum value.
\param port pointer to a \a uint8_t holding the ports aux number, returns the actual port number to use if successful.
\param description pointer to a \a char constant for the pin description.
-\returns true if successful, false if not.
+\returns pointer to a \a #xbar_t structure with details about the claimed port if successful, \a NULL if not.
*/
-bool ioport_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *port, const char *description)
+xbar_t *ioport_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *port, const char *description)
{
- bool ok = false;
+ xbar_t *portinfo = NULL;
if(hal.port.claim) {
- xbar_t *portinfo;
uint8_t hcnt = get_hcount(type, dir);
- if((ok = (portinfo = get_info(type, dir, *port, true)) &&
- // portinfo->cap.claimable && TODO: add?
- !portinfo->mode.claimed &&
- hal.port.claim(type, dir, port, description))) {
+ if((portinfo = get_info(type, dir, *port, true)) &&
+ // portinfo->cap.claimable && TODO: add?
+ !portinfo->mode.claimed &&
+ (portinfo->mode.claimed = hal.port.claim(type, dir, port, description))) {
get_port_data(type, dir)->free = -1;
if(get_hcount(type, dir) == hcnt)
dec_hcount(type, dir);
- }
+ } else
+ portinfo = NULL;
}
- return ok;
+ return portinfo;
}
-/*! \brief Reassign pin function.
-\param port pointer to an \a aux_ctrl_t structure with a valid port number.
-\param function pointer to a \a #pin_function_t enum value to be updated.
-*/
+// Deprecated
void ioport_assign_function (aux_ctrl_t *aux_ctrl, pin_function_t *function)
{
xbar_t *input;
@@ -329,6 +322,7 @@ void ioport_assign_function (aux_ctrl_t *aux_ctrl, pin_function_t *function)
}
}
+// Deprecated
void ioport_assign_out_function (aux_ctrl_out_t *aux_ctrl, pin_function_t *function)
{
xbar_t *output;
@@ -336,21 +330,88 @@ void ioport_assign_out_function (aux_ctrl_out_t *aux_ctrl, pin_function_t *funct
if((output = hal.port.get_pin_info(Port_Digital, Port_Output, aux_ctrl->aux_port))) {
*function = aux_ctrl->function;
- ports_cfg[Port_DigitalOut].bus.mask &= ~(1 << output->id);
+ ports_cfg[Port_DigitalOut].bus.mask &= ~(1UL << output->id);
ports_cfg[Port_DigitalOut].count = ports_cfg[Port_DigitalOut].free = -1;
setting_remove_elements(Settings_IoPort_InvertOut, ports_cfg[Port_DigitalOut].bus.mask);
}
}
-/*! \brief Check if ports can be claimed by aux number or not.
-\returns true if ports can be claimed by aux number, false if not.
+/*! \brief Set pin function.
+\param port pointer to a \a xbar_t structure.
+\param function a \a #pin_function_t enum value.
+\param caps pointer to \a #driver_caps_t capability flags.
*/
-bool ioport_can_claim_explicit (void)
+bool ioport_set_function (xbar_t *pin, pin_function_t function, driver_caps_t caps)
{
- return !!hal.port.claim && !!hal.port.get_pin_info;
+ bool ok = false;
+ io_ports_list_t *io_port = ports;
+ io_ports_private_t *cfg = get_port_data(!pin->mode.analog, pin->mode.output);
+
+ do {
+ if(io_port->ports_id == pin->ports_id) {
+ if((ok = pin->set_function && pin->set_function(pin, function))) {
+
+ cfg->bus.mask &= ~(1 << (pin->id + io_port->ports_id->cfg[pin->mode.output].n_start));
+ cfg->count = cfg->free = -1;
+
+ if(caps.control && !pin->mode.analog && pin->mode.input) {
+
+ hal.signals_cap.mask |= caps.control->mask;
+
+ if(function == Input_Probe || xbar_fn_to_signals_mask(function).mask)
+ setting_remove_elements(Settings_IoPort_InvertIn, cfg->bus.mask);
+
+ } else switch(function) {
+
+ case Output_CoolantMist:
+ hal.coolant_cap.mist = On;
+ break;
+
+ case Output_CoolantFlood:
+ hal.coolant_cap.flood = On;
+ break;
+
+ default: break;
+ }
+ }
+ }
+ } while(!ok && (io_port = io_port->next));
+
+ return ok;
}
+/*! \brief Get basic ioports capabilities.
+\returns a \a #io_port_cando_t union.
+*/
+io_port_cando_t ioports_can_do (void)
+{
+ io_port_cando_t can_do = {};
+
+ if(hal.port.get_pin_info) {
+ can_do.claim_explicit = !!hal.port.claim;
+ can_do.analog_out = !!hal.port.analog_out;
+ can_do.digital_out = !!hal.port.digital_out;
+ can_do.wait_on_input = !!hal.port.wait_on_input;
+ }
+
+ return can_do;
+}
+
+// Deprecated
+bool ioport_can_claim_explicit (void)
+{
+ return ioports_can_do().claim_explicit;
+}
+
+/*! \brief Enumerate ports.
+\param type as an \a #io_port_type_t enum value.
+\param dir as an \a #io_port_direction_t enum value.
+\param filter a \a #pin_cap_t union with fields set that must match the port capabilities.
+\param callback pointer to a \a #ioports_enumerate_callback_ptr function that will be called for each matching port.
+If the function returns \a true the enumeration will end.
+\param data a pointer to context data passed to the callback function.
+*/
bool ioports_enumerate (io_port_type_t type, io_port_direction_t dir, pin_cap_t filter, ioports_enumerate_callback_ptr callback, void *data)
{
bool ok = false;
@@ -383,6 +444,38 @@ bool ioports_enumerate (io_port_type_t type, io_port_direction_t dir, pin_cap_t
return ok;
}
+/*! \brief Set pin description.
+\param type as an \a #io_port_type_t enum value.
+\param dir as an \a #io_port_direction_t enum value.
+\param port the port aux number.
+\param description pointer to a \a char constant for the pin description.
+*/
+bool ioport_set_description (io_port_type_t type, io_port_direction_t dir, uint8_t port, const char *description)
+{
+ if(hal.port.set_pin_description)
+ hal.port.set_pin_description(type, dir, port, description);
+
+ return !!hal.port.set_pin_description;
+}
+
+bool ioport_analog_out (uint8_t port, float value)
+{
+ return hal.port.analog_out && hal.port.analog_out(port, value);
+}
+
+bool ioport_digital_out (uint8_t port, uint32_t value)
+{
+ if(hal.port.digital_out)
+ hal.port.digital_out(port, value != 0);
+
+ return !!hal.port.digital_out;
+}
+
+int32_t ioport_wait_on_input (io_port_type_t type, uint8_t port, wait_mode_t wait_mode, float timeout)
+{
+ return hal.port.wait_on_input ? hal.port.wait_on_input(type, port, wait_mode, timeout) : -1;
+}
+
bool ioport_analog_out_config (uint8_t port, pwm_config_t *config)
{
xbar_t *pin;
@@ -420,10 +513,18 @@ bool ioport_digital_pwm_config (uint8_t port, pwm_config_t *config)
return ok && pin->config(pin, config, false);
}
-/* experimental code follows */
-
// HAL wrapper/veneers
+__attribute__((always_inline)) static inline bool is_match (io_ports_list_t *io_port, io_port_type_t type, io_port_direction_t dir, uint8_t port)
+{
+ return io_port->type == type && port >= io_port->ports_id->cfg[dir].n_start && port <= io_port->ports_id->cfg[dir].idx_last;
+}
+
+__attribute__((always_inline)) static inline const char *pnum_to_string (uint8_t port, const char *pnum)
+{
+ return pnum ? (pnum + (port * 3) + (port > 9 ? port - 10 : 0)) : NULL;
+}
+
static xbar_t *io_get_pin_info (io_port_type_t type, io_port_direction_t dir, uint8_t port)
{
xbar_t *pin = NULL;
@@ -433,10 +534,10 @@ static xbar_t *io_get_pin_info (io_port_type_t type, io_port_direction_t dir, ui
port = cfg->map[port];
do {
- if(io_port && io_port->hal.get_pin_info && port >= io_port->port[cfg->type].n_start && port <= io_port->port[cfg->type].n_end) {
- if((pin = io_port->hal.get_pin_info(dir, port - io_port->port[cfg->type].n_start))) {
- // pin->id = pin->id + io_port->port[cfg->type].n_start; TODO: a new attribute is needed?
- pin->mode.claimed = cfg->claimed.mask & (1UL << pin->id);
+ if(is_match(io_port, type, dir, port)) {
+ if((pin = io_port->hal.get_pin_info(dir, port - io_port->ports_id->cfg[dir].n_start))) {
+ pin->ports_id = io_port->ports_id;
+ pin->mode.claimed = cfg->claimed.mask & (1UL << (pin->id + io_port->ports_id->cfg[dir].n_start));
}
}
} while(pin == NULL && (io_port = io_port->next));
@@ -452,8 +553,8 @@ static void io_set_pin_description (io_port_type_t type, io_port_direction_t dir
port = cfg->map[port];
do {
- if(io_port->hal.set_pin_description && port >= io_port->port[cfg->type].n_start && port <= io_port->port[cfg->type].n_end) {
- io_port->hal.set_pin_description(dir, port - io_port->port[cfg->type].n_start, s);
+ if(is_match(io_port, type, dir, port)) {
+ io_port->hal.set_pin_description(dir, port - io_port->ports_id->cfg[dir].n_start, s);
break;
}
} while((io_port = io_port->next));
@@ -467,11 +568,11 @@ static bool io_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *por
if(!(cfg->claimed.mask & (1UL << *port))) do {
- if(*port >= io_port->port[cfg->type].n_start && *port <= io_port->port[cfg->type].n_end) {
+ if(is_match(io_port, type, dir, *port)) {
xbar_t *pin;
- if((ok = (pin = io_port->hal.get_pin_info(dir, *port - io_port->port[cfg->type].n_start))) && pin->cap.claimable) {
+ if((ok = (pin = io_port->hal.get_pin_info(dir, *port - io_port->ports_id->cfg[dir].n_start))) && pin->cap.claimable) {
uint_fast8_t idx = 0;
@@ -482,10 +583,10 @@ static bool io_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *por
for(; idx < cfg->last_claimed ; idx++) {
if((cfg->map[idx] = cfg->map[idx + 1]) != 255)
- io_set_pin_description(type, dir, idx, (cfg->pnum + (idx * 3) + (idx > 9 ? idx - 10 : 0)));
+ io_set_pin_description(type, dir, idx, pnum_to_string(idx, cfg->pnum));
}
- io_port->hal.set_pin_description(dir, *port - io_port->port[cfg->type].n_start, description);
+ io_port->hal.set_pin_description(dir, *port - io_port->ports_id->cfg[dir].n_start, description);
cfg->map[cfg->last_claimed] = *port;
*port = cfg->last_claimed--;
@@ -506,8 +607,8 @@ static bool io_analog_out (uint8_t port, float value)
port = cfg->map[port];
do {
- if(io_port->hal.analog_out && port >= io_port->port[Port_AnalogOut].n_start && port <= io_port->port[Port_AnalogOut].n_end)
- return io_port->hal.analog_out(port - io_port->port[cfg->type].n_start, value);
+ if(io_port->hal.analog_out && is_match(io_port, Port_Analog, Port_Output, port))
+ return io_port->hal.analog_out(port - io_port->ports_id->cfg[Port_Output].n_start, value);
} while((io_port = io_port->next));
return false;
@@ -521,8 +622,8 @@ static void io_digital_out (uint8_t port, bool on)
port = cfg->map[port];
do {
- if(io_port->hal.digital_out && port >= io_port->port[Port_DigitalOut].n_start && port <= io_port->port[Port_DigitalOut].n_end) {
- io_port->hal.digital_out(port - io_port->port[cfg->type].n_start, on);
+ if(io_port->hal.digital_out && is_match(io_port, Port_Digital, Port_Output, port)) {
+ io_port->hal.digital_out(port - io_port->ports_id->cfg[Port_Output].n_start, on);
break;
}
} while((io_port = io_port->next));
@@ -538,8 +639,8 @@ static int32_t io_wait_on_input (io_port_type_t type, uint8_t port, wait_mode_t
port = cfg->map[port];
do {
- if(io_port->hal.wait_on_input && port >= io_port->port[cfg->type].n_start && port <= io_port->port[cfg->type].n_end) {
- value = io_port->hal.wait_on_input(port - io_port->port[cfg->type].n_start, wait_mode, timeout);
+ if(io_port->hal.wait_on_input && is_match(io_port, type, Port_Input, port)) {
+ value = io_port->hal.wait_on_input(port - io_port->ports_id->cfg[Port_Input].n_start, wait_mode, timeout);
break;
}
} while((io_port = io_port->next));
@@ -556,8 +657,8 @@ static bool io_register_interrupt_handler (uint8_t port, pin_irq_mode_t irq_mode
port = cfg->map[port];
do {
- if(io_port->hal.register_interrupt_handler && port >= io_port->port[Port_DigitalIn].n_start && port <= io_port->port[Port_DigitalIn].n_end)
- return io_port->hal.register_interrupt_handler(port - io_port->port[cfg->type].n_start, user_port, irq_mode, interrupt_callback);
+ if(io_port->hal.register_interrupt_handler && is_match(io_port, Port_Digital, Port_Input, port))
+ return io_port->hal.register_interrupt_handler(port - io_port->ports_id->cfg[Port_Input].n_start, user_port, irq_mode, interrupt_callback);
} while((io_port = io_port->next));
return false;
@@ -571,12 +672,6 @@ static io_ports_list_t *insert_ports (void)
if((io_ports = calloc(sizeof(io_ports_list_t), 1))) {
- uint_fast8_t idx = 4;
-
- do {
- io_ports->port[--idx].n_start = 255;
- } while(idx);
-
if(ports == NULL)
ports = io_ports;
else {
@@ -609,11 +704,30 @@ static bool claim_hal (void)
return hal.port.get_pin_info == io_get_pin_info;
}
+#ifdef IOPORTS_KEEP_DEPRECATED
+
+ISR_CODE uint8_t ISR_FUNC(ioports_map_reverse)(io_ports_detail_t *type, uint8_t port)
+{
+ if(type->map) {
+ uint_fast8_t idx = type->n_ports;
+ do {
+ if(type->map[--idx] == port) {
+ port = idx;
+ break;
+ }
+ } while(idx);
+ }
+
+ return port;
+}
+
static const char *get_pnum (io_ports_data_t *ports, uint8_t port)
{
return ports->pnum ? (ports->pnum + (port * 3) + (port > 9 ? port - 10 : 0)) : NULL;
}
+#endif
+
static uint8_t add_ports (io_ports_detail_t *ports, uint8_t *map, io_port_type_t type, io_port_direction_t dir, uint8_t n_ports)
{
io_ports_private_t *p_data = get_port_data(type, dir);
@@ -626,11 +740,14 @@ static uint8_t add_ports (io_ports_detail_t *ports, uint8_t *map, io_port_type_t
n_ports = p_data->n_max - ports->n_start;
ports->idx_last = ports->n_start + n_ports - 1;
+#ifdef IOPORTS_KEEP_DEPRECATED
ports->map = map;
- if(p_data->ports == NULL) // for now...
+#endif
+ if(p_data->ports == NULL)
p_data->ports = ports;
p_data->count = -1;
- }
+ } else
+ ports->n_start = 255;
p_data->n_ports += n_ports;
ports->n_ports = n_ports;
@@ -638,13 +755,15 @@ static uint8_t add_ports (io_ports_detail_t *ports, uint8_t *map, io_port_type_t
return n_ports;
}
-bool _ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, uint8_t n_out, set_pin_description_ptr set_description)
+static bool _ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, uint8_t n_out, set_pin_description_ptr set_description)
{
uint_fast8_t n_ports;
io_ports_private_t *cfg_in = get_port_data(type, Port_Input),
*cfg_out = get_port_data(type, Port_Output);
+#ifdef IOPORTS_KEEP_DEPRECATED
ports->get_pnum = get_pnum;
+#endif
if(type == Port_Digital) {
@@ -674,16 +793,15 @@ bool _ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, ui
cfg_in->map[i] = cfg_out->map[i] = 255;
} while(i);
- cfg_in->pnum = cfg_out->pnum = ports->pnum = type == Port_Digital ? dpnum : apnum;
+ cfg_in->pnum = cfg_out->pnum /* = ports->pnum*/ = type == Port_Digital ? dpnum : apnum;
for(i = 0; i <= n_ports; i++) {
if(ports->in.n_ports && i >= ports->in.n_start && i <= ports->in.idx_last) {
- if(ports->in.map)
- ports->in.map[idx_in] = i;
+ cfg_in->map[idx_in] = i;
if(set_description)
- set_description(type, Port_Input, i - ports->in.n_start, get_pnum(ports, idx_in));
+ set_description(type, Port_Input, i - ports->in.n_start, pnum_to_string(idx_in, cfg_in->pnum));
idx_in++;
@@ -696,10 +814,9 @@ bool _ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, ui
if(ports->out.n_ports && i >= ports->out.n_start && i <= ports->out.idx_last) {
- if(ports->out.map)
- ports->out.map[idx_out] = i;
+ cfg_out->map[idx_out] = i;
if(set_description)
- set_description(type, Port_Output, i - ports->out.n_start, get_pnum(ports, idx_out));
+ set_description(type, Port_Output, i - ports->out.n_start, pnum_to_string(idx_out, cfg_out->pnum));
if(i < MAX_PORTS) {
cfg_out->bus.mask |= (1 << i);
@@ -745,16 +862,8 @@ bool ioports_add_analog (io_analog_t *analog)
if((ports = insert_ports())) {
- if(analog->ports->in.n_ports) {
- ports->port[Port_AnalogIn].n_start = analog->ports->in.n_start;
- ports->port[Port_AnalogIn].n_end = analog->ports->in.idx_last;
- }
-
- if(analog->ports->out.n_ports) {
- ports->port[Port_AnalogOut].n_start = analog->ports->out.n_start;
- ports->port[Port_AnalogOut].n_end = analog->ports->out.idx_last;
- }
-
+ ports->type = Port_Analog;
+ ports->ports_id = analog->ports;
ports->hal.set_pin_description = analog->set_pin_description;
ports->hal.get_pin_info = analog->get_pin_info;
if(analog->ports->out.n_ports)
@@ -782,16 +891,8 @@ bool ioports_add_digital (io_digital_t *digital)
if((io_ports = insert_ports())) {
- if(digital->ports->in.n_ports) {
- io_ports->port[Port_DigitalIn].n_start = digital->ports->in.n_start;
- io_ports->port[Port_DigitalIn].n_end = digital->ports->in.idx_last;
- }
-
- if(digital->ports->out.n_ports) {
- io_ports->port[Port_DigitalOut].n_start = digital->ports->out.n_start;
- io_ports->port[Port_DigitalOut].n_end = digital->ports->out.idx_last;
- }
-
+ io_ports->type = Port_Digital;
+ io_ports->ports_id = digital->ports;
io_ports->hal.set_pin_description = digital->set_pin_description;
io_ports->hal.get_pin_info = digital->get_pin_info;
if(digital->ports->out.n_ports)
@@ -808,21 +909,6 @@ bool ioports_add_digital (io_digital_t *digital)
return ok;
}
-ISR_CODE uint8_t ISR_FUNC(ioports_map_reverse)(io_ports_detail_t *type, uint8_t port)
-{
- if(type->map) {
- uint_fast8_t idx = type->n_ports;
- do {
- if(type->map[--idx] == port) {
- port = idx;
- break;
- }
- } while(idx);
- }
-
- return port;
-}
-
/*! \brief calculate inverted pwm value if configured
\param pwm_data pointer t a \a spindle_pwm_t structure.
\param pwm_value non inverted PWM value.
diff --git a/ioports.h b/ioports.h
index c5afd20..d220a51 100644
--- a/ioports.h
+++ b/ioports.h
@@ -21,6 +21,8 @@
#pragma once
+//#define IOPORTS_KEEP_DEPRECATED
+
#define IOPORT_UNASSIGNED 255
typedef enum {
@@ -35,14 +37,14 @@ typedef enum {
/*! \brief Pointer to function for setting a digital output.
\param port port number
-\param on true to set output high, false to set it low
+\param on \a true to set output high, \a false to set it low
*/
typedef void (*digital_out_ptr)(uint8_t port, bool on);
/*! \brief Pointer to function for setting an analog output.
\param port port number.
\param value
-\returns true if successful, false otherwise.
+\returns \a true if successful, \a false otherwise.
*/
typedef bool (*analog_out_ptr)(uint8_t port, float value);
@@ -54,7 +56,7 @@ __NOTE:__ The latest value read is stored in \ref #sys sys.var5399.
\param port port number.
\param wait_mode a #wait_mode_t enum value.
\param timeout in seconds, ignored if wait_mode is #WaitMode_Immediate (0).
-\returns read value if successful, -1 otherwise.
+\returns read value if successful, \a -1 otherwise.
*/
typedef int32_t (*wait_on_input_ptr)(io_port_type_t type, uint8_t port, wait_mode_t wait_mode, float timeout);
@@ -66,7 +68,7 @@ __NOTE:__ The latest value read is stored in \ref #sys sys.var5399.
\param port port number.
\param wait_mode a #wait_mode_t enum value.
\param timeout in seconds, ignored if wait_mode is #WaitMode_Immediate (0).
-\returns read value if successful, -1 otherwise.
+\returns read value if successful, \a -1 otherwise.
*/
typedef int32_t (*ll_wait_on_input_ptr)(uint8_t port, wait_mode_t wait_mode, float timeout);
@@ -92,7 +94,7 @@ typedef void (*ll_set_pin_description_ptr)(io_port_direction_t dir, uint8_t port
\param type as an \a #io_port_type_t enum value.
\param dir as an \a #io_port_direction_t enum value.
\param port port number.
-\returns pointer to port information in a xbar_t struct if successful, NULL if not.
+\returns pointer to port information in a \a #xbar_t struct if successful, \a NULL if not.
*/
typedef xbar_t *(*get_pin_info_ptr)(io_port_type_t type, io_port_direction_t dir, uint8_t port);
@@ -101,7 +103,7 @@ typedef xbar_t *(*get_pin_info_ptr)(io_port_type_t type, io_port_direction_t dir
\param type as an \a #io_port_type_t enum value.
\param dir as an \a #io_port_direction_t enum value.
\param port port number.
-\returns pointer to port information in a xbar_t struct if successful, NULL if not.
+\returns pointer to port information in a \a #xbar_t struct if successful, \a NULL if not.
*/
typedef xbar_t *(*ll_get_pin_info_ptr)(io_port_direction_t dir, uint8_t port);
@@ -110,7 +112,7 @@ typedef xbar_t *(*ll_get_pin_info_ptr)(io_port_direction_t dir, uint8_t port);
\param dir as an \a #io_port_direction_t enum value.
\param port port number.
\param description description of the pin function.
-\returns true if successful, false if not.
+\returns \a true if successful, \a false if not.
*/
typedef bool (*claim_port_ptr)(io_port_type_t type, io_port_direction_t dir, uint8_t *port, const char *description);
@@ -119,7 +121,7 @@ typedef bool (*claim_port_ptr)(io_port_type_t type, io_port_direction_t dir, uin
\param dir as an \a #io_port_direction_t enum value.
\param port port number.
\param description description of the pin function.
-\returns true if successful, false if not.
+\returns \a true if successful, \a false if not.
*/
typedef bool (*ll_claim_port_ptr)(io_port_direction_t dir, uint8_t port, uint8_t user_port, const char *description);
@@ -129,13 +131,13 @@ typedef bool (*ll_claim_port_ptr)(io_port_direction_t dir, uint8_t port, uint8_t
\param dir as an \a #io_port_direction_t enum value.
\param port_from port number.
\param port_to port number.
-\returns true if successful, false if not.
+\returns \a true if successful, \a false if not.
*/
typedef bool (*swap_pins_ptr)(io_port_type_t type, io_port_direction_t dir, uint8_t port_from, uint8_t port_to);
/*! \brief Pointer to callback function for input port interrupt events.
\param port port number.
-\param state true if port level is high, false if it is low.
+\param state \a true if port level is high, \a false if it is low.
*/
typedef void (*ioport_interrupt_callback_ptr)(uint8_t port, bool state);
@@ -143,7 +145,7 @@ typedef void (*ioport_interrupt_callback_ptr)(uint8_t port, bool state);
\param port port number.
\param irq_mode a \a #pin_irq_mode_t enum value.
\param interrupt_callback pointer to the callback function to register or NULL to deregister the current callback.
-\returns true if successful, false otherwise.
+\returns \a true if successful, \a false otherwise.
*/
typedef bool (*ioport_register_interrupt_handler_ptr)(uint8_t port, pin_irq_mode_t irq_mode, ioport_interrupt_callback_ptr interrupt_callback);
@@ -152,7 +154,7 @@ typedef bool (*ioport_register_interrupt_handler_ptr)(uint8_t port, pin_irq_mode
\param user_port port number to be used for the callback.
\param irq_mode a \a #pin_irq_mode_t enum value.
\param interrupt_callback pointer to the callback function to register or NULL to deregister the current callback.
-\returns true if successful, false otherwise.
+\returns \a true if successful, \a false otherwise.
*/
typedef bool (*ll_ioport_register_interrupt_handler_ptr)(uint8_t port, uint8_t user_port, pin_irq_mode_t irq_mode, ioport_interrupt_callback_ptr interrupt_callback);
@@ -174,21 +176,46 @@ typedef struct {
ioport_register_interrupt_handler_ptr register_interrupt_handler;
} io_port_t;
+typedef union {
+ control_signals_t *control;
+ coolant_state_t *coolant;
+ limit_signals_t *limits;
+} driver_caps_t __attribute__ ((__transparent_union__));
+
+typedef union {
+ uint8_t io;
+ struct {
+ uint8_t claim_explicit :1,
+ digital_out :1,
+ analog_out :1,
+ wait_on_input :1,
+ configure :1;
+ };
+} io_port_cando_t;
+
uint8_t ioports_available (io_port_type_t type, io_port_direction_t dir);
uint8_t ioports_unclaimed (io_port_type_t type, io_port_direction_t dir);
xbar_t *ioport_get_info (io_port_type_t type, io_port_direction_t dir, uint8_t port);
-bool ioport_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *port, const char *description);
-bool ioport_can_claim_explicit (void);
+xbar_t *ioport_claim (io_port_type_t type, io_port_direction_t dir, uint8_t *port, const char *description);
+io_port_cando_t ioports_can_do (void);
uint8_t ioport_find_free (io_port_type_t type, io_port_direction_t dir, pin_cap_t filter, const char *description);
bool ioports_enumerate (io_port_type_t type, io_port_direction_t dir, pin_cap_t filter, ioports_enumerate_callback_ptr callback, void *data);
-void ioport_assign_function (aux_ctrl_t *aux_ctrl, pin_function_t *function);
-void ioport_assign_out_function (aux_ctrl_out_t *aux_ctrl, pin_function_t *function);
+bool ioport_set_description (io_port_type_t type, io_port_direction_t dir, uint8_t port, const char *description);
+bool ioport_set_function (xbar_t *pin, pin_function_t function, driver_caps_t caps);
+bool ioport_analog_out (uint8_t port, float value);
+bool ioport_digital_out (uint8_t port, uint32_t value);
+int32_t ioport_wait_on_input (io_port_type_t type, uint8_t port, wait_mode_t wait_mode, float timeout);
bool ioport_analog_out_config (uint8_t port, pwm_config_t *config);
bool ioport_digital_pwm_config (uint8_t port, pwm_config_t *config);
bool ioport_digital_in_config (uint8_t port, gpio_in_config_t *config);
bool ioport_enable_irq (uint8_t port, pin_irq_mode_t irq_mode, ioport_interrupt_callback_ptr handler);
bool ioport_digital_out_config (uint8_t port, gpio_out_config_t *config);
+bool ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, uint8_t n_out); //!< Deprecated - use ioports_add_analog() or ioports_add_digital() instead.
+bool ioport_can_claim_explicit (void); //!< Deprecated - use ioports_can_do() instead.
+void ioport_assign_function (aux_ctrl_t *aux_ctrl, pin_function_t *function); //!< Deprecated - use ioport_set_function() instead.
+void ioport_assign_out_function (aux_ctrl_out_t *aux_ctrl, pin_function_t *function); //!< Deprecated - use ioport_set_function() instead.
+
//
struct io_ports_data;
@@ -197,14 +224,23 @@ typedef struct {
uint8_t n_ports;
uint8_t n_start;
uint8_t idx_last;
+#ifdef IOPORTS_KEEP_DEPRECATED
uint8_t *map; //!< Deprecated - do not reference in new code!
+#endif
} io_ports_detail_t;
typedef struct io_ports_data {
- const char *pnum; //!< Deprecated - do not reference in new code!
- io_ports_detail_t in;
- io_ports_detail_t out;
+ union {
+ io_ports_detail_t cfg[2];
+ struct {
+ io_ports_detail_t in;
+ io_ports_detail_t out;
+ };
+ };
+#ifdef IOPORTS_KEEP_DEPRECATED
+ const char *pnum; //!< Deprecated - do not reference in new code!
const char *(*get_pnum)(struct io_ports_data *data, uint8_t port); //!< Deprecated - do not reference in new code!
+#endif
} io_ports_data_t;
typedef struct {
@@ -237,17 +273,18 @@ typedef struct {
bool always_on;
} ioports_pwm_t;
-bool ioports_add (io_ports_data_t *ports, io_port_type_t type, uint8_t n_in, uint8_t n_out); //!< Deprecated - do not use in new code!
bool ioports_add_analog (io_analog_t *ports);
bool ioports_add_digital (io_digital_t *ports);
void ioports_add_settings (driver_settings_load_ptr settings_loaded, setting_changed_ptr setting_changed);
void ioport_save_input_settings (xbar_t *xbar, gpio_in_config_t *config);
void ioport_save_output_settings (xbar_t *xbar, gpio_out_config_t *config);
void ioport_setting_changed (setting_id_t id);
-#define iports_get_pnum(type, port) type.get_pnum(&type, port)
-#define ioports_map(type, port) ( type.map ? type.map[port] : port )
uint8_t ioports_map_reverse (io_ports_detail_t *type, uint8_t port);
bool ioports_precompute_pwm_values (pwm_config_t *config, ioports_pwm_t *pwm_data, uint32_t clock_hz);
uint_fast16_t ioports_compute_pwm_value (ioports_pwm_t *pwm_data, float value);
+#ifdef IOPORTS_KEEP_DEPRECATED
+#define iports_get_pnum(type, port) type.get_pnum(&type, port)
+#define ioports_map(type, port) ( type.map ? type.map[port] : port )
+#endif
/*EOF*/
diff --git a/pin_bits_masks.h b/pin_bits_masks.h
index 1551c6b..39e3e57 100644
--- a/pin_bits_masks.h
+++ b/pin_bits_masks.h
@@ -496,6 +496,9 @@ static aux_ctrl_out_t aux_ctrl_out[] = {
#endif
{ .function = Output_CoProc_Boot0, .aux_port = 0xFF, .pin = COPROC_BOOT0_PIN, .port = (void *)COPROC_BOOT0_PORT },
#endif
+#if defined(SPI_RST_PIN) && SPI_RST_PORT == EXPANDER_PORT && defined(RP2040)
+ { .function = Output_SPIRST, .aux_port = 0xFF, .pin = SPI_RST_PIN, .port = (void *)SPI_RST_PORT },
+#endif
};
static inline aux_ctrl_out_t *aux_out_remap_explicit (void *port, uint8_t pin, uint8_t aux_port, void *output)
@@ -539,10 +542,8 @@ static inline void aux_ctrl_claim_out_ports (aux_claim_explicit_out_ptr aux_clai
for(idx = 0; idx < sizeof(aux_ctrl_out) / sizeof(aux_ctrl_out_t); idx++) {
if(aux_ctrl_out[idx].port == (void *)EXPANDER_PORT) {
if(ioports_enumerate(Port_Digital, Port_Output, (pin_cap_t){ .external = On, .claimable = On }, aux_claim, &aux_ctrl_out[idx])) {
- if(ioport_claim(Port_Digital, Port_Output, &aux_ctrl_out[idx].aux_port, ""/*xbar_fn_to_pinname(aux_ctrl_out[idx].function)*/)) {
- aux_ctrl_out[idx].output = hal.port.get_pin_info(Port_Digital, Port_Output, aux_ctrl_out[idx].aux_port);
- if(((xbar_t *)aux_ctrl_out[idx].output)->set_function)
- ((xbar_t *)aux_ctrl_out[idx].output)->set_function((xbar_t *)aux_ctrl_out[idx].output, aux_ctrl_out[idx].function);
+ if((aux_ctrl_out[idx].output = ioport_claim(Port_Digital, Port_Output, &aux_ctrl_out[idx].aux_port, NULL /*xbar_fn_to_pinname(aux_ctrl_out[idx].function)*/))) {
+ ioport_set_function((xbar_t *)aux_ctrl_out[idx].output, aux_ctrl_out[idx].function, NULL);
// TODO: else set description?
aux_claim_explicit(&aux_ctrl_out[idx]);
}
diff --git a/protocol.c b/protocol.c
index 9952710..0e406ca 100644
--- a/protocol.c
+++ b/protocol.c
@@ -1073,9 +1073,10 @@ ISR_CODE bool ISR_FUNC(protocol_enqueue_foreground_task)(fg_task_ptr fn, void *d
if((ok = bptr != realtime_queue.tail)) { // If not buffer full
realtime_queue.task[realtime_queue.head].data = data;
- realtime_queue.task[realtime_queue.head].task = fn; // add function pointer to buffer,
+ realtime_queue.task[realtime_queue.head].task = fn; // add function pointer to buffer,
realtime_queue.head = bptr; // update pointer and
- system_set_exec_state_flag(EXEC_RT_COMMAND); // flag it for execute
+ if(sys.driver_started)
+ system_set_exec_state_flag(EXEC_RT_COMMAND); // flag it for execute
}
return ok;
diff --git a/system.c b/system.c
index 2d0e097..cb62964 100644
--- a/system.c
+++ b/system.c
@@ -814,7 +814,7 @@ const char *help_pins (const char *cmd)
const char *help_pin_state (const char *cmd)
{
- return hal.port.get_pin_info ? "output auxiliary pin states" : NULL;
+ return ioports_can_do().io ? "output auxiliary pin states" : NULL;
}
#endif