Ver código fonte

Re-Arm bugfixes (#7495)

* UBL_correction

* RGB Map function
Tannoo 6 anos atrás
pai
commit
859fa35287

+ 3
- 3
Marlin/G26_Mesh_Validation_Tool.cpp Ver arquivo

@@ -134,14 +134,14 @@
134 134
     extern char lcd_status_message[];
135 135
   #endif
136 136
   extern float destination[XYZE];
137
-  void set_destination_to_current();
137
+  extern void set_destination_to_current() { COPY(destination, current_position); }
138 138
   void prepare_move_to_destination();
139 139
   #if AVR_AT90USB1286_FAMILY  // Teensyduino & Printrboard IDE extensions have compile errors without this
140 140
     inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
141 141
     inline void set_current_to_destination() { COPY(current_position, destination); }
142 142
   #else
143
-    void sync_plan_position_e();
144
-    void set_current_to_destination();
143
+    extern void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
144
+    extern void set_current_to_destination() { COPY(current_position, destination); }
145 145
   #endif
146 146
   #if ENABLED(NEWPANEL)
147 147
     void lcd_setstatusPGM(const char* const message, const int8_t level);

+ 24
- 11
Marlin/src/HAL/HAL_LPC1768/arduino.cpp Ver arquivo

@@ -140,17 +140,27 @@ bool digitalRead(int pin) {
140 140
   return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
141 141
 }
142 142
 
143
-void analogWrite(int pin, int pin_status) { //todo: Hardware PWM
144
-  /*
145
-  if (pin == P2_4) {
146
-    LPC_PWM1->MR5 = pin_status; // set value
147
-    LPC_PWM1->LER = _BV(5); // set latch
148
-  }
149
-  else if (pin == P2_5) {
150
-    LPC_PWM1->MR6 = pin_status;
151
-    LPC_PWM1->LER = _BV(6);
143
+void analogWrite(int pin, int pwm_value) {
144
+/*
145
+  if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
146
+    return;
147
+
148
+  int old_pin = pin;
149
+  int old_value = pwm_value;
150
+
151
+  if(old_value != 0) {
152
+    for(uint16_t x = 0; x <= 5000; x++) {
153
+      LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
154
+      //digitalWrite(old_pin, HIGH);
155
+      delayMicroseconds(old_value);
156
+      LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
157
+      //pinMode(pin, OUTPUT);
158
+      //digitalWrite(old_pin, LOW);
159
+      delayMicroseconds(255 - old_value);
160
+    }
152 161
   }
153
-  */
162
+*/
163
+
154 164
 }
155 165
 
156 166
 extern bool HAL_adc_finished();
@@ -175,7 +185,6 @@ void eeprom_read_block (void *__dst, const void *__src, size_t __n) { }
175 185
 
176 186
 void eeprom_update_block (const void *__src, void *__dst, size_t __n) { }
177 187
 
178
-/***/
179 188
 char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s) {
180 189
   char format_string[20];
181 190
   snprintf(format_string, 20, "%%%d.%df", __width, __prec);
@@ -195,4 +204,8 @@ void randomSeed(uint32_t value) {
195 204
   srand(value);
196 205
 }
197 206
 
207
+int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max) {
208
+  return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
209
+}
210
+
198 211
 #endif // TARGET_LPC1768

+ 2
- 0
Marlin/src/HAL/HAL_LPC1768/arduino.h Ver arquivo

@@ -112,4 +112,6 @@ void randomSeed(uint32_t);
112 112
 
113 113
 char *dtostrf (double __val, signed char __width, unsigned char __prec, char *__s);
114 114
 
115
+int map(uint16_t x, uint16_t in_min, uint16_t in_max, uint16_t out_min, uint16_t out_max);
116
+
115 117
 #endif // __ARDUINO_DEF_H__

Carregando…
Cancelar
Salvar