This commit is contained in:
shrkey
2016-10-09 22:39:10 +01:00
parent af917c9174
commit 7cf6027b80
2 changed files with 6 additions and 3 deletions

View File

@@ -195,7 +195,7 @@ void DW640::allOff() {
/* DC Motor specific code */ /* DC Motor specific code */
void DW640::setMotorSpeed(uint8_t motor, uint16_t speed) { void DW640::setMotorSpeed(uint8_t motor, int16_t speed) {
uint8_t in1; uint8_t in1;
uint8_t in2; uint8_t in2;
@@ -267,17 +267,20 @@ void DW640::runMotor( uint8_t control, uint8_t in1, uint8_t in2, uint16_t speed
setPin( in1, 0 ); setPin( in1, 0 );
} }
} else { // DW_ININ } else { // DW_ININ
printf( "here" );
if( control == DW_FORWARD ) { if( control == DW_FORWARD ) {
printf( "FWD %d %d %d \n", speed, in1, in2 );
setPin( in2, 0 ); setPin( in2, 0 );
setPWM( in1, 0, speed * 16 ); setPWM( in1, 0, speed * 16 );
} else if( control == DW_REVERSE ) { } else if( control == DW_REVERSE ) {
printf( "REV %d %d %d \n", speed, in1, in2 );
setPin( in1, 0 ); setPin( in1, 0 );
setPWM( in2, 0, speed * 16 ); setPWM( in2, 0, speed * 16 );
} else if( control == DW_STOP ) { } else if( control == DW_STOP ) {
printf( "STP %d %d %d \n", speed, in1, in2 );
setPin( in1, 1 ); setPin( in1, 1 );
setPin( in2, 1 ); setPin( in2, 1 );
} else if( control == DW_COAST ) { } else if( control == DW_COAST ) {
printf( "CST %d %d %d \n", speed, in1, in2 );
setPin( in1, 0 ); setPin( in1, 0 );
setPin( in2, 0 ); setPin( in2, 0 );
} }

View File

@@ -87,7 +87,7 @@ class DW640 {
void allOff(); void allOff();
void setMotorSpeed(uint8_t motor, uint16_t speed); void setMotorSpeed(uint8_t motor, int16_t speed);
void setMotorOff(uint8_t motor); void setMotorOff(uint8_t motor);
void runMotor( uint8_t control, uint8_t in1, uint8_t in2, uint16_t speed ); void runMotor( uint8_t control, uint8_t in1, uint8_t in2, uint16_t speed );