Browse Source

Misc. general cleanup

Scott Lahteine 7 years ago
parent
commit
b9327a4d16

+ 121
- 132
Marlin/src/HAL/HAL_LPC1768/HAL_LCD_I2C_routines.c View File

23
 // adapted from  I2C/master/master.c example
23
 // adapted from  I2C/master/master.c example
24
 //   https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
24
 //   https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
25
 
25
 
26
+#ifdef TARGET_LPC1768
26
 
27
 
28
+#ifdef __cplusplus
29
+  extern "C" {
30
+#endif
27
 
31
 
28
-#if defined(TARGET_LPC1768)
29
-
30
-  #ifdef __cplusplus
31
-    extern "C" {
32
-  #endif
32
+#include <lpc17xx_i2c.h>
33
+#include <lpc17xx_pinsel.h>
34
+#include <lpc17xx_libcfg_default.h>
33
 
35
 
34
-  #include <lpc17xx_i2c.h>
35
-  #include <lpc17xx_pinsel.h>
36
-  #include <lpc17xx_libcfg_default.h>
36
+//////////////////////////////////////////////////////////////////////////////////////
37
 
37
 
38
-  //////////////////////////////////////////////////////////////////////////////////////
38
+// These two routines are exact copies of the lpc17xx_i2c.c routines.  Couldn't link to
39
+// to the lpc17xx_i2c.c routines so had to copy them into this file & rename them.
39
 
40
 
40
-  // These two routines are exact copies of the lpc17xx_i2c.c routines.  Couldn't link to
41
-  // to the lpc17xx_i2c.c routines so had to copy them into this file & rename them.
41
+static uint32_t _I2C_Start (LPC_I2C_TypeDef *I2Cx) {
42
+  // Reset STA, STO, SI
43
+  I2Cx->I2CONCLR = I2C_I2CONCLR_SIC|I2C_I2CONCLR_STOC|I2C_I2CONCLR_STAC;
42
 
44
 
43
-  static uint32_t _I2C_Start (LPC_I2C_TypeDef *I2Cx)
44
-  {
45
-    // Reset STA, STO, SI
46
-    I2Cx->I2CONCLR = I2C_I2CONCLR_SIC|I2C_I2CONCLR_STOC|I2C_I2CONCLR_STAC;
45
+  // Enter to Master Transmitter mode
46
+  I2Cx->I2CONSET = I2C_I2CONSET_STA;
47
 
47
 
48
-    // Enter to Master Transmitter mode
49
-    I2Cx->I2CONSET = I2C_I2CONSET_STA;
48
+  // Wait for complete
49
+  while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
50
+  I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
51
+  return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
52
+}
50
 
53
 
51
-    // Wait for complete
52
-    while (!(I2Cx->I2CONSET & I2C_I2CONSET_SI));
54
+static void _I2C_Stop (LPC_I2C_TypeDef *I2Cx) {
55
+  /* Make sure start bit is not active */
56
+  if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
53
     I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
57
     I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
54
-    return (I2Cx->I2STAT & I2C_STAT_CODE_BITMASK);
55
-  }
56
-
57
-  static void _I2C_Stop (LPC_I2C_TypeDef *I2Cx)
58
-  {
59
 
58
 
60
-    /* Make sure start bit is not active */
61
-    if (I2Cx->I2CONSET & I2C_I2CONSET_STA)
62
-    {
63
-      I2Cx->I2CONCLR = I2C_I2CONCLR_STAC;
64
-    }
59
+  I2Cx->I2CONSET = I2C_I2CONSET_STO|I2C_I2CONSET_AA;
60
+  I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
61
+}
65
 
62
 
66
-    I2Cx->I2CONSET = I2C_I2CONSET_STO|I2C_I2CONSET_AA;
63
+//////////////////////////////////////////////////////////////////////////////////////
67
 
64
 
68
-    I2Cx->I2CONCLR = I2C_I2CONCLR_SIC;
69
-  }
65
+#define U8G_I2C_OPT_FAST 16  // from u8g.h
70
 
66
 
67
+#define USEDI2CDEV_M            1
71
 
68
 
72
-  //////////////////////////////////////////////////////////////////////////////////////
69
+#define I2CDEV_S_ADDR   0x78  // from SSD1306  //actual address is 0x3C - shift left 1 with LSB set to 0 to indicate write
73
 
70
 
74
-  #define U8G_I2C_OPT_FAST 16  // from u8g.h
71
+#define BUFFER_SIZE                     0x1  // only do single byte transfers with LCDs
75
 
72
 
76
-  #define USEDI2CDEV_M            1
77
-
78
-  #define I2CDEV_S_ADDR   0x78  // from SSD1306  //actual address is 0x3C - shift left 1 with LSB set to 0 to indicate write
79
-
80
-  #define BUFFER_SIZE                     0x1  // only do single byte transfers with LCDs
73
+#if (USEDI2CDEV_M == 0)
74
+  #define I2CDEV_M LPC_I2C0
75
+#elif (USEDI2CDEV_M == 1)
76
+  #define I2CDEV_M LPC_I2C1
77
+#elif (USEDI2CDEV_M == 2)
78
+  #define I2CDEV_M LPC_I2C2
79
+#else
80
+  #error "Master I2C device not defined!"
81
+#endif
81
 
82
 
82
-  #if (USEDI2CDEV_M == 0)
83
-    #define I2CDEV_M LPC_I2C0
84
-  #elif (USEDI2CDEV_M == 1)
85
-    #define I2CDEV_M LPC_I2C1
86
-  #elif (USEDI2CDEV_M == 2)
87
-    #define I2CDEV_M LPC_I2C2
88
-  #else
89
-    #error "Master I2C device not defined!"
83
+PINSEL_CFG_Type PinCfg;
84
+I2C_M_SETUP_Type transferMCfg;
85
+
86
+#define I2C_status (LPC_I2C1->I2STAT & I2C_STAT_CODE_BITMASK)
87
+
88
+uint8_t u8g_i2c_start(uint8_t sla) {  // send slave address and write bit
89
+  // Sometimes TX data ACK or NAK status is returned.  That mean the start state didn't
90
+  // happen which means only the value of the slave address was send.  Keep looping until
91
+  // the slave address and write bit are actually sent.
92
+  do{
93
+    _I2C_Stop(I2CDEV_M); // output stop state on I2C bus
94
+    _I2C_Start(I2CDEV_M); // output start state on I2C bus
95
+    while ((I2C_status != I2C_I2STAT_M_TX_START)
96
+        && (I2C_status != I2C_I2STAT_M_TX_RESTART)
97
+        && (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
98
+        && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK));  //wait for start to be asserted
99
+
100
+    LPC_I2C1->I2CONCLR = I2C_I2CONCLR_STAC; // clear start state before tansmitting slave address
101
+    LPC_I2C1->I2DAT = I2CDEV_S_ADDR & I2C_I2DAT_BITMASK; // transmit slave address & write bit
102
+    LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
103
+    LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
104
+    while ((I2C_status != I2C_I2STAT_M_TX_SLAW_ACK)
105
+        && (I2C_status != I2C_I2STAT_M_TX_SLAW_NACK)
106
+        && (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
107
+        && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK));  //wait for slaw to finish
108
+  }while ( (I2C_status == I2C_I2STAT_M_TX_DAT_ACK) ||  (I2C_status == I2C_I2STAT_M_TX_DAT_NACK));
109
+  return 1;
110
+}
111
+
112
+void u8g_i2c_init(uint8_t clock_option) {
113
+
114
+  /**
115
+   * Init I2C pin connect
116
+   */
117
+  PinCfg.OpenDrain = 0;
118
+  PinCfg.Pinmode = 0;
119
+  #if ((USEDI2CDEV_M == 0))
120
+    PinCfg.Funcnum = 1;
121
+    PinCfg.Pinnum = 27;
122
+    PinCfg.Portnum = 0;
123
+    PINSEL_ConfigPin(&PinCfg); // SDA0 / D57  AUX-1
124
+    PinCfg.Pinnum = 28;
125
+    PINSEL_ConfigPin(&PinCfg); // SCL0 / D58  AUX-1
90
   #endif
126
   #endif
127
+  #if ((USEDI2CDEV_M == 1))
128
+    PinCfg.Funcnum = 3;
129
+    PinCfg.Pinnum = 0;
130
+    PinCfg.Portnum = 0;
131
+    PINSEL_ConfigPin(&PinCfg);  // SDA1 / D20 SCA
132
+    PinCfg.Pinnum = 1;
133
+    PINSEL_ConfigPin(&PinCfg);  // SCL1 / D21 SCL
134
+  #endif
135
+  #if ((USEDI2CDEV_M == 2))
136
+    PinCfg.Funcnum = 2;
137
+    PinCfg.Pinnum = 10;
138
+    PinCfg.Portnum = 0;
139
+    PINSEL_ConfigPin(&PinCfg); // SDA2 / D38  X_ENABLE_PIN
140
+    PinCfg.Pinnum = 11;
141
+    PINSEL_ConfigPin(&PinCfg); // SCL2 / D55  X_DIR_PIN
142
+  #endif
143
+  // Initialize I2C peripheral
144
+  I2C_Init(I2CDEV_M, (clock_option & U8G_I2C_OPT_FAST) ? 400000: 100000);  // LCD data rates
91
 
145
 
146
+  // Enable Master I2C operation
147
+  I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
92
 
148
 
93
-  PINSEL_CFG_Type PinCfg;
94
-  I2C_M_SETUP_Type transferMCfg;
95
-
96
-  #define I2C_status (LPC_I2C1->I2STAT & I2C_STAT_CODE_BITMASK)
97
-
98
-
99
-  uint8_t u8g_i2c_start(uint8_t sla) {  // send slave address and write bit
100
-    // Sometimes TX data ACK or NAK status is returned.  That mean the start state didn't
101
-    // happen which means only the value of the slave address was send.  Keep looping until
102
-    // the slave address and write bit are actually sent.
103
-    do{
104
-      _I2C_Stop(I2CDEV_M); // output stop state on I2C bus
105
-      _I2C_Start(I2CDEV_M); // output start state on I2C bus
106
-      while ((I2C_status != I2C_I2STAT_M_TX_START)
107
-          && (I2C_status != I2C_I2STAT_M_TX_RESTART)
108
-          && (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
109
-          && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK));  //wait for start to be asserted
110
-
111
-      LPC_I2C1->I2CONCLR = I2C_I2CONCLR_STAC; // clear start state before tansmitting slave address
112
-      LPC_I2C1->I2DAT = I2CDEV_S_ADDR & I2C_I2DAT_BITMASK; // transmit slave address & write bit
113
-      LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
114
-      LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
115
-      while ((I2C_status != I2C_I2STAT_M_TX_SLAW_ACK)
116
-          && (I2C_status != I2C_I2STAT_M_TX_SLAW_NACK)
117
-          && (I2C_status != I2C_I2STAT_M_TX_DAT_ACK)
118
-          && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK));  //wait for slaw to finish
119
-    }while ( (I2C_status == I2C_I2STAT_M_TX_DAT_ACK) ||  (I2C_status == I2C_I2STAT_M_TX_DAT_NACK));
120
-    return 1;
121
-  }
149
+  u8g_i2c_start(0); // send slave address and write bit
150
+}
122
 
151
 
152
+volatile extern uint32_t _millis;
153
+uint8_t u8g_i2c_send_byte(uint8_t data) {
154
+  #define I2C_TIMEOUT 3
155
+  LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
156
+  LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
157
+  LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
158
+  uint32_t timeout = _millis + I2C_TIMEOUT;
159
+  while ((I2C_status != I2C_I2STAT_M_TX_DAT_ACK) && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK) && (timeout > _millis));  // wait for xmit to finish
160
+  // had hangs with SH1106 so added time out - have seen temporary screen corruption when this happens
161
+  return 1;
162
+}
123
 
163
 
124
-  void u8g_i2c_init(uint8_t clock_option) {
125
-
126
-    /*
127
-      * Init I2C pin connect
128
-    */
129
-    PinCfg.OpenDrain = 0;
130
-    PinCfg.Pinmode = 0;
131
-    #if ((USEDI2CDEV_M == 0))
132
-      PinCfg.Funcnum = 1;
133
-      PinCfg.Pinnum = 27;
134
-      PinCfg.Portnum = 0;
135
-      PINSEL_ConfigPin(&PinCfg); // SDA0 / D57  AUX-1
136
-      PinCfg.Pinnum = 28;
137
-      PINSEL_ConfigPin(&PinCfg); // SCL0 / D58  AUX-1
138
-    #endif
139
-    #if ((USEDI2CDEV_M == 1))
140
-      PinCfg.Funcnum = 3;
141
-      PinCfg.Pinnum = 0;
142
-      PinCfg.Portnum = 0;
143
-      PINSEL_ConfigPin(&PinCfg);  // SDA1 / D20 SCA
144
-      PinCfg.Pinnum = 1;
145
-      PINSEL_ConfigPin(&PinCfg);  // SCL1 / D21 SCL
146
-    #endif
147
-    #if ((USEDI2CDEV_M == 2))
148
-      PinCfg.Funcnum = 2;
149
-      PinCfg.Pinnum = 10;
150
-      PinCfg.Portnum = 0;
151
-      PINSEL_ConfigPin(&PinCfg); // SDA2 / D38  X_ENABLE_PIN
152
-      PinCfg.Pinnum = 11;
153
-      PINSEL_ConfigPin(&PinCfg); // SCL2 / D55  X_DIR_PIN
154
-    #endif
155
-    // Initialize I2C peripheral
156
-    I2C_Init(I2CDEV_M, (clock_option & U8G_I2C_OPT_FAST) ? 400000: 100000);  // LCD data rates
157
-
158
-    /* Enable Master I2C operation */
159
-    I2C_Cmd(I2CDEV_M, I2C_MASTER_MODE, ENABLE);
160
-
161
-    u8g_i2c_start(0); // send slave address and write bit
162
-  }
164
+void u8g_i2c_stop(void) {
165
+}
163
 
166
 
164
-  volatile extern uint32_t _millis;
165
-  uint8_t u8g_i2c_send_byte(uint8_t data) {
166
-    #define I2C_TIMEOUT 3
167
-    LPC_I2C1->I2DAT = data & I2C_I2DAT_BITMASK; // transmit data
168
-    LPC_I2C1->I2CONSET = I2C_I2CONSET_AA;
169
-    LPC_I2C1->I2CONCLR = I2C_I2CONCLR_SIC;
170
-    uint32_t timeout = _millis + I2C_TIMEOUT;
171
-    while ((I2C_status != I2C_I2STAT_M_TX_DAT_ACK) && (I2C_status != I2C_I2STAT_M_TX_DAT_NACK) && (timeout > _millis));  // wait for xmit to finish
172
-    // had hangs with SH1106 so added time out - have seen temporary screen corruption when this happens
173
-    return 1;
174
-  }
175
 
167
 
176
-  void u8g_i2c_stop(void) {
168
+#ifdef __cplusplus
177
   }
169
   }
178
-
179
-
180
-  #ifdef __cplusplus
181
-    }
182
-  #endif
183
 #endif
170
 #endif
171
+
172
+#endif // TARGET_LPC1768

+ 6
- 10
Marlin/src/HAL/HAL_LPC1768/arduino.cpp View File

72
 // IO functions
72
 // IO functions
73
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
73
 // As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
74
 void pinMode(pin_t pin, uint8_t mode) {
74
 void pinMode(pin_t pin, uint8_t mode) {
75
-  if (!VALID_PIN(pin))
76
-    return;
75
+  if (!VALID_PIN(pin)) return;
77
 
76
 
78
   PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
77
   PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
79
                              LPC1768_PIN_PIN(pin),
78
                              LPC1768_PIN_PIN(pin),
100
 }
99
 }
101
 
100
 
102
 void digitalWrite(pin_t pin, uint8_t pin_status) {
101
 void digitalWrite(pin_t pin, uint8_t pin_status) {
103
-  if (!VALID_PIN(pin))
104
-    return;
102
+  if (!VALID_PIN(pin)) return;
105
 
103
 
106
   if (pin_status)
104
   if (pin_status)
107
     LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
105
     LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
120
 }
118
 }
121
 
119
 
122
 bool digitalRead(pin_t pin) {
120
 bool digitalRead(pin_t pin) {
123
-  if (!VALID_PIN(pin)) {
124
-    return false;
125
-  }
121
+  if (!VALID_PIN(pin)) return false;
122
+
126
   return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
123
   return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
127
 }
124
 }
128
 
125
 
129
 void analogWrite(pin_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
126
 void analogWrite(pin_t pin, int pwm_value) {  // 1 - 254: pwm_value, 0: LOW, 255: HIGH
127
+  if (!VALID_PIN(pin)) return;
128
+
130
   #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
129
   #define MR0_MARGIN 200       // if channel value too close to MR0 the system locks up
131
 
130
 
132
   static bool out_of_PWM_slots = false;
131
   static bool out_of_PWM_slots = false;
133
 
132
 
134
-  if (!VALID_PIN(pin))
135
-    return;
136
-
137
   uint value = MAX(MIN(pwm_value, 255), 0);
133
   uint value = MAX(MIN(pwm_value, 255), 0);
138
   if (value == 0 || value == 255) {  // treat as digital pin
134
   if (value == 0 || value == 255) {  // treat as digital pin
139
     LPC1768_PWM_detach_pin(pin);    // turn off PWM
135
     LPC1768_PWM_detach_pin(pin);    // turn off PWM

+ 1
- 0
Marlin/src/HAL/HAL_LPC1768/pinmapping.h View File

22
 
22
 
23
 #ifndef __HAL_PINMAPPING_H__
23
 #ifndef __HAL_PINMAPPING_H__
24
 #define __HAL_PINMAPPING_H__
24
 #define __HAL_PINMAPPING_H__
25
+
25
 #include "../../core/macros.h"
26
 #include "../../core/macros.h"
26
 
27
 
27
 #include <stdint.h>
28
 #include <stdint.h>

+ 0
- 1
Marlin/src/core/macros.h View File

43
 #define _O2          __attribute__((optimize("O2")))
43
 #define _O2          __attribute__((optimize("O2")))
44
 #define _O3          __attribute__((optimize("O3")))
44
 #define _O3          __attribute__((optimize("O3")))
45
 
45
 
46
-
47
 // Clock speed factors
46
 // Clock speed factors
48
 #define CYCLES_PER_MICROSECOND (F_CPU / 1000000L) // 16 or 20
47
 #define CYCLES_PER_MICROSECOND (F_CPU / 1000000L) // 16 or 20
49
 #define INT0_PRESCALER 8
48
 #define INT0_PRESCALER 8

+ 2
- 2
Marlin/src/inc/Version.h View File

27
 
27
 
28
 /**
28
 /**
29
  * This file is the standard Marlin version identifier file, all fields can be
29
  * This file is the standard Marlin version identifier file, all fields can be
30
- * overriden by the ones defined on _Version.h by using the Configuration.h
30
+ * overriden by the ones defined in _Version.h by using the Configuration.h
31
  * directive USE_AUTOMATIC_VERSIONING.
31
  * directive USE_AUTOMATIC_VERSIONING.
32
  */
32
  */
33
 
33
 
53
    * here we define this default string as the date where the latest release
53
    * here we define this default string as the date where the latest release
54
    * version was tagged.
54
    * version was tagged.
55
    */
55
    */
56
-  #define STRING_DISTRIBUTION_DATE "2017-10-19 12:00"
56
+  #define STRING_DISTRIBUTION_DATE "2017-11-19 12:00"
57
 
57
 
58
   /**
58
   /**
59
    * Required minimum Configuration.h and Configuration_adv.h file versions.
59
    * Required minimum Configuration.h and Configuration_adv.h file versions.

Loading…
Cancel
Save