Skip to content

Commit

Permalink
Improved version and compatible to latest BlueDisplay
Browse files Browse the repository at this point in the history
  • Loading branch information
ArminJo committed Nov 25, 2024
1 parent c634bd5 commit 248a3f8
Show file tree
Hide file tree
Showing 23 changed files with 565 additions and 169 deletions.
2 changes: 2 additions & 0 deletions src/ADCUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -607,6 +607,8 @@ uint16_t getVoltageMillivoltWith_1_1VoltReference(uint8_t aADCChannelForVoltageM

/*
* Return true if sVCCVoltageMillivolt is > 4.3 V and < 4.95 V
* This does not really work for the UNO board, because it has no series Diode in the USB VCC
* and therefore a very low voltage drop.
*/
bool isVCCUSBPowered() {
readVCCVoltageMillivolt();
Expand Down
2 changes: 1 addition & 1 deletion src/AutonomousDrive.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,7 @@ void driveCollisonAvoidingOneStep() {

#if !defined(ENABLE_USER_PROVIDED_COLLISION_DETECTION)
if (sCurrentPage == PAGE_AUTOMATIC_CONTROL) {
char tStringBuffer[6];
char tStringBuffer[11];
sprintf_P(tStringBuffer, PSTR("%2d%s"), sCentimetersDrivenPerScan, "cm/scan");
BlueDisplay1.drawText(TEXT_SIZE_11_WIDTH, BUTTON_HEIGHT_4_LINE_4 - TEXT_SIZE_11_HEIGHT - TEXT_SIZE_11_DECEND,
tStringBuffer, TEXT_SIZE_11, COLOR16_BLACK, COLOR16_WHITE);
Expand Down
42 changes: 22 additions & 20 deletions src/AutonomousDrivePage.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,15 +31,15 @@ BDButton TouchButtonStepMode;
const char sStepModeButtonStringContinuousStepToTurn[] PROGMEM = "Continuous\n->\nStep to turn";
const char sStepModeButtonStringStepToTurnSingleStep[] PROGMEM = "Step to turn\n->\nSingle step";
const char sStepModeButtonStringSingleStepContinuous[] PROGMEM = "Single step\n->\nContinuous";
const char *const sStepModeButtonCaptionStringArray[] PROGMEM = { sStepModeButtonStringContinuousStepToTurn,
const char *const sStepModeButtonTextStringArray[] PROGMEM = { sStepModeButtonStringContinuousStepToTurn,
sStepModeButtonStringStepToTurnSingleStep, sStepModeButtonStringSingleStepContinuous };

#if defined(ENABLE_DISTANCE_FEEDBACK_MODE)
BDButton TouchButtonDistanceFeedbackMode;
const char sDistanceFeedbackModeNoTone[] PROGMEM = "No tone";
const char sDistanceFeedbackModePentatonic[] PROGMEM = "Pentatonic";
const char sDistanceFeedbackModeContinuous[] PROGMEM = "Continuous";
const char *const sDistanceFeedbackModeButtonCaptionStringArray[] PROGMEM = { sDistanceFeedbackModeNoTone,
const char *const sDistanceFeedbackModeButtonTextStringArray[] PROGMEM = { sDistanceFeedbackModeNoTone,
sDistanceFeedbackModePentatonic, sDistanceFeedbackModeContinuous };
#endif

Expand All @@ -57,13 +57,13 @@ const char sDistanceSourceModeButtonStringMaxUS[] PROGMEM = "Max->US";
# if defined(CAR_HAS_IR_DISTANCE_SENSOR)
const char sDistanceSourceModeButtonStringUSIr[] PROGMEM = "US->IR";
const char sDistanceSourceModeButtonStringIrMin[] PROGMEM = "IR->Min";
const char *const sDistanceSourceModeButtonCaptionStringArray[] PROGMEM = { sDistanceSourceModeButtonStringMinMax,
const char *const sDistanceSourceModeButtonTextStringArray[] PROGMEM = { sDistanceSourceModeButtonStringMinMax,
sDistanceSourceModeButtonStringMaxUS, sDistanceSourceModeButtonStringUSIr, sDistanceSourceModeButtonStringIrMin };
# else
const char sDistanceSourceModeButtonStringUSTof[] PROGMEM = "US->ToF";
const char sDistanceSourceModeButtonStringTofMin[] PROGMEM = "ToF->Min";

const char * const sDistanceSourceModeButtonCaptionStringArray[] PROGMEM = { sDistanceSourceModeButtonStringMinMax, sDistanceSourceModeButtonStringMaxUS,
const char * const sDistanceSourceModeButtonTextStringArray[] PROGMEM = { sDistanceSourceModeButtonStringMinMax, sDistanceSourceModeButtonStringMaxUS,
sDistanceSourceModeButtonStringUSTof, sDistanceSourceModeButtonStringTofMin};
# endif
#endif
Expand All @@ -75,8 +75,8 @@ BDButton TouchButtonStartStopBuiltInAutonomousDrive;
BDButton TouchButtonFollower;

#if defined(ENABLE_DISTANCE_FEEDBACK_MODE)
void setDistanceFeedbackModeButtonCaption() {
TouchButtonDistanceFeedbackMode.setCaptionFromStringArrayPGM(sDistanceFeedbackModeButtonCaptionStringArray, sDistanceFeedbackMode, true);
void setDistanceFeedbackModeButtonText() {
TouchButtonDistanceFeedbackMode.setTextFromStringArrayPGM(sDistanceFeedbackModeButtonTextStringArray, sDistanceFeedbackMode, true);
}

#pragma GCC diagnostic ignored "-Wunused-parameter"
Expand All @@ -86,12 +86,12 @@ void doNextDistanceFeedbackMode(BDButton *aTheTouchedButton, int16_t aValue) {
sDistanceFeedbackMode = DISTANCE_FEEDBACK_NO_TONE;
noTone(BUZZER_PIN);
}
setDistanceFeedbackModeButtonCaption();
setDistanceFeedbackModeButtonText();
}
#endif

void setStepModeButtonCaption() {
TouchButtonStepMode.setCaptionFromStringArray((const __FlashStringHelper* const*) sStepModeButtonCaptionStringArray, sStepMode, (sCurrentPage == PAGE_AUTOMATIC_CONTROL));
void setStepModeButtonText() {
TouchButtonStepMode.setTextFromStringArray((const __FlashStringHelper* const*) sStepModeButtonTextStringArray, sStepMode, (sCurrentPage == PAGE_AUTOMATIC_CONTROL));
}

/*
Expand All @@ -105,7 +105,7 @@ void setStepMode(uint8_t aStepMode) {
sDoStep = true;
}
sStepMode = aStepMode;
setStepModeButtonCaption();
setStepModeButtonText();
}

#pragma GCC diagnostic ignored "-Wunused-parameter"
Expand All @@ -132,16 +132,16 @@ void doStep(BDButton *aTheTouchedButton, int16_t aValue) {
}

#if defined(CAR_HAS_IR_DISTANCE_SENSOR) || defined(CAR_HAS_TOF_DISTANCE_SENSOR)
void setScanModeButtonCaption() {
TouchButtonScanMode.setCaptionFromStringArray(sDistanceSourceModeButtonCaptionStringArray, sDistanceSourceMode);
void setScanModeButtonText() {
TouchButtonScanMode.setTextFromStringArray(sDistanceSourceModeButtonTextStringArray, sDistanceSourceMode);
}

void doDistanceSourceMode(BDButton *aTheTouchedButton, int16_t aValue) {
sDistanceSourceMode++;
if (sDistanceSourceMode > DISTANCE_LAST_SOURCE_MODE) {
sDistanceSourceMode = DISTANCE_SOURCE_MODE_MINIMUM;
}
setScanModeButtonCaption();
setScanModeButtonText();
TouchButtonScanMode.drawButton();
}

Expand Down Expand Up @@ -203,7 +203,7 @@ void initAutonomousDrivePage(void) {

TouchButtonScanSpeed.init(0, BUTTON_HEIGHT_6_LINE_4, BUTTON_WIDTH_3_5, BUTTON_HEIGHT_8, COLOR16_BLACK, F("Scan slow"), TEXT_SIZE_14,
FLAG_BUTTON_DO_BEEP_ON_TOUCH | FLAG_BUTTON_TYPE_TOGGLE_RED_GREEN, false, &doChangeScanSpeed);
TouchButtonScanSpeed.setCaptionForValueTrue("Scan fast");
TouchButtonScanSpeed.setTextForValueTrue("Scan fast");

#if defined(ENABLE_PATH_INFO_PAGE)
TouchButtonPathInfoPage.init(BUTTON_WIDTH_3_POS_3, 0, BUTTON_WIDTH_3, BUTTON_HEIGHT_6, COLOR16_RED, F("Show Path"), TEXT_SIZE_11,
Expand All @@ -217,7 +217,7 @@ void initAutonomousDrivePage(void) {
BUTTON_WIDTH_3, TEXT_SIZE_22_HEIGHT, COLOR16_RED, F("Start User"), TEXT_SIZE_14,
FLAG_BUTTON_DO_BEEP_ON_TOUCH | FLAG_BUTTON_TYPE_TOGGLE_RED_GREEN, (sDriveMode == MODE_COLLISION_AVOIDING_USER),
&doStartStopTestUser);
TouchButtonStartStopUserAutonomousDrive.setCaptionForValueTrue(F("Stop User"));
TouchButtonStartStopUserAutonomousDrive.setTextForValueTrue(F("Stop User"));
#endif

#if defined(ENABLE_DISTANCE_FEEDBACK_MODE)
Expand All @@ -238,12 +238,12 @@ void initAutonomousDrivePage(void) {
TouchButtonStartStopBuiltInAutonomousDrive.init(0, BUTTON_HEIGHT_4_LINE_4, BUTTON_WIDTH_3, BUTTON_HEIGHT_4, COLOR16_RED,
F("Start\nBuiltin"), TEXT_SIZE_22, FLAG_BUTTON_DO_BEEP_ON_TOUCH | FLAG_BUTTON_TYPE_TOGGLE_RED_GREEN,
(sDriveMode == MODE_COLLISION_AVOIDING_BUILTIN), &doStartStopAutomomousDrive);
TouchButtonStartStopBuiltInAutonomousDrive.setCaptionForValueTrue(F("Stop"));
TouchButtonStartStopBuiltInAutonomousDrive.setTextForValueTrue(F("Stop"));

TouchButtonFollower.init(BUTTON_WIDTH_3_POS_2, BUTTON_HEIGHT_4_LINE_4, BUTTON_WIDTH_3, BUTTON_HEIGHT_4,
COLOR16_RED, F("Start\nFollow"), TEXT_SIZE_22, FLAG_BUTTON_DO_BEEP_ON_TOUCH | FLAG_BUTTON_TYPE_TOGGLE_RED_GREEN,
(sDriveMode == MODE_FOLLOWER), &doStartStopFollowerMode);
TouchButtonFollower.setCaptionForValueTrue(F("Stop\nFollow"));
TouchButtonFollower.setTextForValueTrue(F("Stop\nFollow"));
}

void drawAutonomousDrivePage(void) {
Expand Down Expand Up @@ -288,12 +288,12 @@ void startAutonomousDrivePage(void) {
handleAutomomousDriveRadioButtons();

// restore last step and scan mode
setStepModeButtonCaption();
setStepModeButtonText();
#if defined(CAR_HAS_IR_DISTANCE_SENSOR) || defined(CAR_HAS_TOF_DISTANCE_SENSOR)
setScanModeButtonCaption();
setScanModeButtonText();
#endif
#if defined(ENABLE_DISTANCE_FEEDBACK_MODE)
setDistanceFeedbackModeButtonCaption();
setDistanceFeedbackModeButtonText();
#endif
#if defined(ENABLE_PATH_INFO_PAGE)
#define SLIDER_SHIFTED_Y_POS BUTTON_HEIGHT_6
Expand All @@ -309,9 +309,11 @@ void startAutonomousDrivePage(void) {
SliderIROrTofDistance.setPosition(POS_X_DISTANCE_POSITION_SLIDER - (TEXT_SIZE_11_WIDTH + BUTTON_WIDTH_10), SLIDER_SHIFTED_Y_POS);
#endif
drawAutonomousDrivePage();
#if defined(VIN_ATTENUATED_INPUT_PIN)
if(!isPWMCalibrated) {
calibrateDriveSpeedPWMAndPrint();
}
#endif
}

// currently not used
Expand Down
11 changes: 7 additions & 4 deletions src/CarPWMMotorControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,14 +141,17 @@ class CarPWMMotorControl {
* Functions for moving a fixed distance
*/
// With signed distance
void startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
uint8_t aRequestedDirection); // only setup values
void startGoDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection); // only setup values
void startGoDistanceMillimeter(int aRequestedDistanceMillimeter); // only setup values, no movement -> use updateMotors()

void startGoDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection); // only setup values
void startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
uint8_t aRequestedDirection)__attribute__ ((deprecated ("Renamed to startGoDistanceMillimeterWithSpeed()."))); // only setup values
void goDistanceMillimeter(int aRequestedDistanceMillimeter, void (*aLoopCallback)(void) = NULL); // Blocking function, uses waitUntilStopped
void goDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, int aRequestedDistanceMillimeter, void (*aLoopCallback)(void) = NULL); // Blocking function, uses waitUntilStopped
void goDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection,
void (*aLoopCallback)(void) = NULL); // Blocking function, uses waitUntilStopped
void startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, int aRequestedDistanceMillimeter); // only setup values
void startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
uint8_t aRequestedDirection); // only setup values

bool checkAndHandleDirectionChange(uint8_t aRequestedDirection); // used internally

Expand Down
45 changes: 31 additions & 14 deletions src/CarPWMMotorControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -553,13 +553,17 @@ void CarPWMMotorControl::startRampUpAndWaitForDriveSpeedPWM(uint8_t aRequestedDi
}

void CarPWMMotorControl::startGoDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection) {
startGoDistanceMillimeter(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, aRequestedDirection);
startGoDistanceMillimeterWithSpeed(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, aRequestedDirection);
}

void CarPWMMotorControl::startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
uint8_t aRequestedDirection) {
startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter, aRequestedDirection);
}
/*
* initialize motorInfo fields LastDirection and CompensatedSpeedPWM
*/
void CarPWMMotorControl::startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
void CarPWMMotorControl::startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter,
uint8_t aRequestedDirection) {

#if defined(USE_MPU6050_IMU)
Expand All @@ -572,26 +576,34 @@ void CarPWMMotorControl::startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, u
setSpeedPWMWithRamp(aRequestedSpeedPWM, aRequestedDirection);
#else
checkAndHandleDirectionChange(aRequestedDirection);
rightCarMotor.startGoDistanceMillimeter(aRequestedSpeedPWM, aRequestedDistanceMillimeter, aRequestedDirection);
leftCarMotor.startGoDistanceMillimeter(aRequestedSpeedPWM, aRequestedDistanceMillimeter, aRequestedDirection);
rightCarMotor.startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter, aRequestedDirection);
leftCarMotor.startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter, aRequestedDirection);
#endif
}

void CarPWMMotorControl::goDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection,
void (*aLoopCallback)(void)) {
startGoDistanceMillimeter(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, aRequestedDirection);
startGoDistanceMillimeterWithSpeed(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, aRequestedDirection);
waitUntilStopped(aLoopCallback);
}

void CarPWMMotorControl::startGoDistanceMillimeter(int aRequestedDistanceMillimeter) {
if (aRequestedDistanceMillimeter < 0) {
aRequestedDistanceMillimeter = -aRequestedDistanceMillimeter;
startGoDistanceMillimeter(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, DIRECTION_BACKWARD);
startGoDistanceMillimeterWithSpeed(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, DIRECTION_BACKWARD);
} else {
startGoDistanceMillimeter(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, DIRECTION_FORWARD);
startGoDistanceMillimeterWithSpeed(rightCarMotor.DriveSpeedPWMFor2Volt, aRequestedDistanceMillimeter, DIRECTION_FORWARD);
}
}

void CarPWMMotorControl::startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, int aRequestedDistanceMillimeter) {
if (aRequestedDistanceMillimeter < 0) {
aRequestedDistanceMillimeter = -aRequestedDistanceMillimeter;
startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter, DIRECTION_BACKWARD);
} else {
startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter, DIRECTION_FORWARD);
}
}
/**
* Wait until distance is reached
* @param aLoopCallback called until car has stopped to avoid blocking
Expand All @@ -601,6 +613,11 @@ void CarPWMMotorControl::goDistanceMillimeter(int aRequestedDistanceMillimeter,
waitUntilStopped(aLoopCallback);
}

void CarPWMMotorControl::goDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, int aRequestedDistanceMillimeter, void (*aLoopCallback)(void)) {
startGoDistanceMillimeterWithSpeed(aRequestedSpeedPWM, aRequestedDistanceMillimeter);
waitUntilStopped(aLoopCallback);
}

/*
* Stop car (with ramp)
*/
Expand Down Expand Up @@ -797,8 +814,8 @@ void CarPWMMotorControl::startRotate(int aRotationDegrees, turn_direction_t aTur
tLeftMotorIfPositiveTurn->setSpeedPWMAndDirection(tTurnSpeedPWMLeft, DIRECTION_BACKWARD);
}
#else
tRightMotorIfPositiveTurn->startGoDistanceMillimeter(tTurnSpeedPWMRight, tDistanceMillimeterRight, DIRECTION_FORWARD);
tLeftMotorIfPositiveTurn->startGoDistanceMillimeter(tTurnSpeedPWMLeft, tDistanceMillimeterLeft, DIRECTION_BACKWARD);
tRightMotorIfPositiveTurn->startGoDistanceMillimeterWithSpeed(tTurnSpeedPWMRight, tDistanceMillimeterRight, DIRECTION_FORWARD);
tLeftMotorIfPositiveTurn->startGoDistanceMillimeterWithSpeed(tTurnSpeedPWMLeft, tDistanceMillimeterLeft, DIRECTION_BACKWARD);
#endif
}

Expand Down Expand Up @@ -942,16 +959,16 @@ uint8_t CarPWMMotorControl::getTurnDistanceHalfDegree() {

void CarPWMMotorControl::printCalibrationValues(Print *aSerial) {
aSerial->println(F("Calibration values:"));
aSerial->print(F("mm/256 deg="));
aSerial->print(RobotCar.MillimeterPer256Degree);
aSerial->print(F(" inPlace="));
aSerial->println(RobotCar.MillimeterPer256DegreeInPlace);
aSerial->print(F("2 volt PWM right="));
aSerial->print(F(" mm per 256 deg, "));
aSerial->print(RobotCar.MillimeterPer256DegreeInPlace);
aSerial->println(F(" mm for inPlace"));
aSerial->print(F("PWM for 2 volt: right="));
#if defined(CAR_HAS_4_MECANUM_WHEELS)
aSerial->println(RobotCar.rightCarMotor.DriveSpeedPWMFor2Volt);
#else
aSerial->print(RobotCar.rightCarMotor.DriveSpeedPWMFor2Volt);
aSerial->print(F(" left="));
aSerial->print(F(", left="));
aSerial->println(RobotCar.leftCarMotor.DriveSpeedPWMFor2Volt);
#endif
aSerial->println();
Expand Down
19 changes: 10 additions & 9 deletions src/Distance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,16 @@
#include "HCSR04.hpp" // include sources
#include "RobotCarConfigurations.h" // helps the pretty printer / Ctrl F

#if defined(CAR_HAS_SERVO) && defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#define DISABLE_SERVO_TIMER_AUTO_INITIALIZE // saves 70 bytes program space
#if defined(CAR_HAS_DISTANCE_SERVO)
# if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#include "LightweightServo.hpp"
#endif
# if defined(_LIGHTWEIGHT_SERVO_HPP)
LightweightServo DistanceServo; // The pan servo instance for distance sensor
# else // LightweightServo is not applicable for this CPU
#undef USE_LIGHTWEIGHT_SERVO_LIBRARY
# endif
# endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)

#if defined(CAR_HAS_DISTANCE_SERVO)
# if !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
Servo DistanceServo; // The pan servo instance for distance sensor
# endif
Expand Down Expand Up @@ -87,7 +91,7 @@ ForwardDistancesInfoStruct sForwardDistancesInfo;
void initDistance() {
getDistanceModesFromPins();

#if defined(CAR_HAS_DISTANCE_SERVO) && !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#if defined(CAR_HAS_DISTANCE_SERVO)
DistanceServo.attach(DISTANCE_SERVO_PIN);
#endif

Expand Down Expand Up @@ -492,11 +496,8 @@ void DistanceServoWriteAndWaitForStop(uint8_t aTargetDegrees, bool doWaitForStop
// The servo is top down and therefore inverted
aTargetDegrees = 180 - aTargetDegrees;
#endif
#if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
write10(aTargetDegrees);
#else
DistanceServo.write(aTargetDegrees);
#endif


/*
* Delay until stopped
Expand Down
5 changes: 3 additions & 2 deletions src/EncoderMotor.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
/*
* EncoderMotor.h
*
* Created on: 12.05.2019
* Copyright (C) 2019-2020 Armin Joachimsmeyer
* armin.joachimsmeyer@gmail.com
*
Expand Down Expand Up @@ -79,7 +78,9 @@ class EncoderMotor: public PWMDcMotor {
*/
void startGoDistanceMillimeter(int aRequestedDistanceMillimeter); // Signed distance count
void startGoDistanceMillimeter(unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection);
void startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection);
void startGoDistanceMillimeter(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection)__attribute__ ((deprecated ("Renamed to startGoDistanceMillimeterWithSpeed().")));
void startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, int aRequestedDistanceMillimeter); // Signed distance count
void startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, unsigned int aRequestedDistanceMillimeter, uint8_t aRequestedDirection);
bool updateMotor();

/*
Expand Down
Loading

0 comments on commit 248a3f8

Please sign in to comment.