diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
index 62e545cee3e78bff5e7add5d1dfe5ecc0553e1a4..af37501774a7175fed349625b90380b259e15e39 100644
--- a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
+++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.cpp
@@ -113,7 +113,7 @@
     servo_info[this->servoIndex].Pin.isActive = false;
   }
 
-  void Servo::write(const int value) {
+  void Servo::write(int value) {
     if (value < MIN_PULSE_WIDTH) { // treat values less than 544 as angles in degrees (valid values in microseconds are handled as microseconds)
       value = map(constrain(value, 0, 180), 0, 180, SERVO_MIN(), SERVO_MAX());
         // odd - this sets zero degrees to 544 and 180 degrees to 2400 microseconds but the literature says
@@ -122,7 +122,7 @@
     this->writeMicroseconds(value);
   }
 
-  void Servo::writeMicroseconds(const int value) {
+  void Servo::writeMicroseconds(int value) {
     // calculate and store the values for the given channel
     byte channel = this->servoIndex;
     if (channel < MAX_SERVOS) {  // ensure channel is valid
diff --git a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h
index 79737e64ca2f20ddf2c449b2b0c57c1135e0e26c..f0d6f048a5892e4c11f6798fea918ae07c2f94e5 100644
--- a/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h
+++ b/Marlin/src/HAL/HAL_LPC1768/LPC1768_Servo.h
@@ -42,9 +42,9 @@
       int8_t attach(const int pin);            // attach the given pin to the next free channel, set pinMode, return channel number (-1 on fail)
       int8_t attach(const int pin, const int min, const int max); // as above but also sets min and max values for writes.
       void detach();
-      void write(const int value);             // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
-      void writeMicroseconds(const int value); // write pulse width in microseconds
-      void move(const int value);              // attach the servo, then move to value
+      void write(int value);             // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
+      void writeMicroseconds(int value); // write pulse width in microseconds
+      void move(const int value);        // attach the servo, then move to value
                                          // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
                                          // if DEACTIVATE_SERVOS_AFTER_MOVE wait SERVO_DELAY, then detach
       int read();                        // returns current pulse width as an angle between 0 and 180 degrees