lab 4 finished
This commit is contained in:
parent
89113917dc
commit
1b89bef1dd
|
@ -2,8 +2,6 @@
|
||||||
|
|
||||||
#include "inc/msp432p401r.h"
|
#include "inc/msp432p401r.h"
|
||||||
|
|
||||||
#define BUMP_PINS 0b11101101
|
|
||||||
|
|
||||||
void BumpInit(void) {
|
void BumpInit(void) {
|
||||||
// Port 4 pins 0, 2, 3, 5, 6, 7
|
// Port 4 pins 0, 2, 3, 5, 6, 7
|
||||||
// and enables internal resistors
|
// and enables internal resistors
|
||||||
|
|
|
@ -3,6 +3,7 @@
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#define BUMP_PINS 0b11101101
|
||||||
// Set port pins Port 4.0, 4.2, 4.3, 4.5, 4.6 and 4.7 and enable internal resistors as needed
|
// Set port pins Port 4.0, 4.2, 4.3, 4.5, 4.6 and 4.7 and enable internal resistors as needed
|
||||||
void BumpInit(void);
|
void BumpInit(void);
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,145 @@
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include "motor_simple.h"
|
||||||
|
|
||||||
|
#include "bump.h"
|
||||||
|
#include "systick.h"
|
||||||
|
|
||||||
|
#include "inc/msp432p401r.h"
|
||||||
|
|
||||||
|
|
||||||
|
#define BIT0 (uint8_t)(0x01)
|
||||||
|
#define BIT1 (uint8_t)(0x02)
|
||||||
|
#define BIT2 (uint8_t)(0x04)
|
||||||
|
#define BIT3 (uint8_t)(0x08)
|
||||||
|
#define BIT4 (uint8_t)(0x10)
|
||||||
|
#define BIT5 (uint8_t)(0x20)
|
||||||
|
#define BIT6 (uint8_t)(0x40)
|
||||||
|
#define BIT7 (uint8_t)(0x80)
|
||||||
|
|
||||||
|
|
||||||
|
// Left motor (PH) direction connected to P5.4 (J3.29)
|
||||||
|
#define LEFT_DIR_PIN BIT4 // P5.4
|
||||||
|
// Right motor (PH) direction connected to P5.5 (J3.30)
|
||||||
|
#define RIGHT_DIR_PIN BIT5 // P5.5
|
||||||
|
|
||||||
|
// Left motor (EN) PWM connected to P2.7/TA0CCP4 (J4.40)
|
||||||
|
#define LEFT_PWM_PIN BIT7 // P2.7
|
||||||
|
// Right motor (EN) PWM connected to P2.6/TA0CCP3 (J4.39)
|
||||||
|
#define RIGHT_PWM_PIN BIT6 // P2.6
|
||||||
|
|
||||||
|
// Left motor (nSLEEP) enable connected to P3.7 (J4.31)
|
||||||
|
#define LEFT_SLEEP_PIN BIT7 // P3.7
|
||||||
|
// Right motor (nSLEEP) enable connected to P3.6 (J2.11)
|
||||||
|
#define RIGHT_SLEEP_PIN BIT6 // P3.6
|
||||||
|
|
||||||
|
|
||||||
|
// Initializes the 6 GPIO output lines and puts driver to sleep
|
||||||
|
void MotorInit(void) {
|
||||||
|
P5->SEL0 &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN); // GPIO enable
|
||||||
|
P5->SEL1 &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN);
|
||||||
|
P5->DIR |= (LEFT_DIR_PIN | RIGHT_DIR_PIN); // Output direction
|
||||||
|
P5->OUT &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN); // Initialize low
|
||||||
|
|
||||||
|
// motor enable pins - P2.6 P2.7
|
||||||
|
P2->SEL0 |= (LEFT_PWM_PIN | RIGHT_PWM_PIN); // TimerA function
|
||||||
|
P2->SEL1 &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN);
|
||||||
|
P2->DIR |= (LEFT_PWM_PIN | RIGHT_PWM_PIN); // Output direction
|
||||||
|
|
||||||
|
// motor sleep pins - P3.6 P3.7
|
||||||
|
P3->SEL0 &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // GPIO enable
|
||||||
|
P3->SEL1 &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN);
|
||||||
|
P3->DIR |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // Output direction
|
||||||
|
P3->OUT &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // Initialize low (sleep mode)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Stops both motors, puts driver to sleep
|
||||||
|
void MotorStop(void) {
|
||||||
|
P2->OUT &= ~0xC0; // off
|
||||||
|
P3->OUT &= ~0xC0; // low current sleep mode
|
||||||
|
}
|
||||||
|
|
||||||
|
// Drives both motors forward at duty (100 to 9900)
|
||||||
|
// Runs for time duration, and then stops
|
||||||
|
// Stop the motors and return if any bumper switch is active
|
||||||
|
void MotorForward(uint16_t duty, uint32_t times_10ms) {
|
||||||
|
// set direction - PH low
|
||||||
|
P5->OUT &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN);
|
||||||
|
|
||||||
|
// wake up motors
|
||||||
|
P3->OUT |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN);
|
||||||
|
|
||||||
|
// Set PWM duty cycle
|
||||||
|
TIMER_A0->CCR[3] = duty; // Right motor (P2.6/TA0.3)
|
||||||
|
TIMER_A0->CCR[4] = duty; // Left motor (P2.7/TA0.4)
|
||||||
|
|
||||||
|
while(times_10ms--) {
|
||||||
|
Delay10ms(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Drives both motors backward at duty (100 to 9900)
|
||||||
|
// Runs for time duration, and then stops
|
||||||
|
// Runs even if any bumper switch is active
|
||||||
|
void MotorBackward(uint16_t duty, uint32_t times_10ms) {
|
||||||
|
// set direction - PH high
|
||||||
|
P5->OUT |= (LEFT_DIR_PIN | RIGHT_DIR_PIN);
|
||||||
|
|
||||||
|
// wake up motors
|
||||||
|
P3->OUT |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN);
|
||||||
|
|
||||||
|
// Set PWM duty cycle
|
||||||
|
TIMER_A0->CCR[3] = duty; // Right motor (P2.6/TA0.3)
|
||||||
|
TIMER_A0->CCR[4] = duty; // Left motor (P2.7/TA0.4)
|
||||||
|
|
||||||
|
while(times_10ms--) {
|
||||||
|
Delay10ms(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Drives just the left motor forward at duty (100 to 9900)
|
||||||
|
// Right motor is stopped (sleeping)
|
||||||
|
// Runs for time duration, and then stops
|
||||||
|
// Stop the motor and return if any bumper switch is active
|
||||||
|
void MotorLeft(uint16_t duty, uint32_t times_10ms) {
|
||||||
|
// set direction - PH low
|
||||||
|
P5->OUT &= ~LEFT_DIR_PIN;
|
||||||
|
|
||||||
|
// wake up motors
|
||||||
|
P3->OUT = (P3->OUT & ~RIGHT_SLEEP_PIN) | LEFT_SLEEP_PIN;
|
||||||
|
|
||||||
|
// Set PWM duty cycle
|
||||||
|
TIMER_A0->CCR[3] = 0; // Right motor off
|
||||||
|
TIMER_A0->CCR[4] = duty; // Left motor on
|
||||||
|
|
||||||
|
while(times_10ms--) {
|
||||||
|
Delay10ms(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Drives just the right motor forward at duty (100 to 9900)
|
||||||
|
// Left motor is stopped (sleeping)
|
||||||
|
// Runs for time duration, and then stops
|
||||||
|
// Stop the motor and return if any bumper switch is active
|
||||||
|
void MotorRight(uint16_t duty, uint32_t times_10ms) {
|
||||||
|
// set direction - PH low
|
||||||
|
P5->OUT &= ~RIGHT_DIR_PIN;
|
||||||
|
|
||||||
|
// wake up motors
|
||||||
|
P3->OUT = (P3->OUT & ~LEFT_SLEEP_PIN) | RIGHT_SLEEP_PIN;
|
||||||
|
|
||||||
|
// Set PWM duty cycle
|
||||||
|
TIMER_A0->CCR[3] = duty; // Right motor off
|
||||||
|
TIMER_A0->CCR[4] = 0; // Left motor on
|
||||||
|
|
||||||
|
while(times_10ms--) {
|
||||||
|
Delay10ms(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
|
}
|
|
@ -6,38 +6,116 @@
|
||||||
|
|
||||||
#include "inc/msp432p401r.h"
|
#include "inc/msp432p401r.h"
|
||||||
|
|
||||||
// Left motor (PH) direction connected to P5.4 (J3.29)
|
#undef BIT0
|
||||||
// Left motor (EN) PWM connected to P2.7/TA0CCP4 (J4.40)
|
#undef BIT1
|
||||||
// Left motor (nSLEEP) enable connected to P3.7 (J4.31)
|
#undef BIT2
|
||||||
|
#undef BIT3
|
||||||
|
#undef BIT4
|
||||||
|
#undef BIT5
|
||||||
|
#undef BIT6
|
||||||
|
#undef BIT7
|
||||||
|
|
||||||
|
#define BIT0 (uint8_t)(0x01)
|
||||||
|
#define BIT1 (uint8_t)(0x02)
|
||||||
|
#define BIT2 (uint8_t)(0x04)
|
||||||
|
#define BIT3 (uint8_t)(0x08)
|
||||||
|
#define BIT4 (uint8_t)(0x10)
|
||||||
|
#define BIT5 (uint8_t)(0x20)
|
||||||
|
#define BIT6 (uint8_t)(0x40)
|
||||||
|
#define BIT7 (uint8_t)(0x80)
|
||||||
|
|
||||||
|
// duty := H/(H+L) = H/10000
|
||||||
|
// H+L is always 10 000 microsecond
|
||||||
|
|
||||||
|
// Left motor (PH) direction connected to P5.4 (J3.29)
|
||||||
|
#define LEFT_DIR_PIN BIT4 // P5.4
|
||||||
// Right motor (PH) direction connected to P5.5 (J3.30)
|
// Right motor (PH) direction connected to P5.5 (J3.30)
|
||||||
|
#define RIGHT_DIR_PIN BIT5 // P5.5
|
||||||
|
|
||||||
|
// Left motor (EN) PWM connected to P2.7/TA0CCP4 (J4.40)
|
||||||
|
#define LEFT_PWM_PIN BIT7 // P2.7
|
||||||
// Right motor (EN) PWM connected to P2.6/TA0CCP3 (J4.39)
|
// Right motor (EN) PWM connected to P2.6/TA0CCP3 (J4.39)
|
||||||
|
#define RIGHT_PWM_PIN BIT6 // P2.6
|
||||||
|
|
||||||
|
// Left motor (nSLEEP) enable connected to P3.7 (J4.31)
|
||||||
|
#define LEFT_SLEEP_PIN BIT7 // P3.7
|
||||||
// Right motor (nSLEEP) enable connected to P3.6 (J2.11)
|
// Right motor (nSLEEP) enable connected to P3.6 (J2.11)
|
||||||
|
#define RIGHT_SLEEP_PIN BIT6 // P3.6
|
||||||
|
|
||||||
|
|
||||||
// Initializes the 6 GPIO output lines and puts driver to sleep
|
// Initializes the 6 GPIO output lines and puts driver to sleep
|
||||||
void MotorInit(void) {
|
void MotorInit(void) {
|
||||||
// write this code
|
// 1. Configure all motor control pins as outputs
|
||||||
|
// P5.4 (Left DIR), P5.5 (Right DIR)
|
||||||
|
P5->SEL0 &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN); // GPIO function
|
||||||
|
P5->SEL1 &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN);
|
||||||
|
P5->DIR |= (LEFT_DIR_PIN | RIGHT_DIR_PIN); // Output direction
|
||||||
|
|
||||||
|
// P3.6 (Right SLEEP), P3.7 (Left SLEEP)
|
||||||
|
P3->SEL0 &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // GPIO function
|
||||||
|
P3->SEL1 &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN);
|
||||||
|
P3->DIR |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // Output direction
|
||||||
|
|
||||||
|
// P2.6 (Right EN), P2.7 (Left EN)
|
||||||
|
P2->SEL0 &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN); // GPIO function
|
||||||
|
P2->SEL1 &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN);
|
||||||
|
P2->DIR |= (LEFT_PWM_PIN | RIGHT_PWM_PIN); // Output direction
|
||||||
|
|
||||||
|
// 2. Initial state: disable motors
|
||||||
|
P3->OUT &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // SLEEP pins low - DRV8838 disabled
|
||||||
|
P2->OUT &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN); // EN pins low
|
||||||
|
|
||||||
|
SysTickWait1us(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Stops both motors, puts driver to sleep
|
// Stops both motors, puts driver to sleep
|
||||||
void MotorStop(void) {
|
void MotorStop(void) {
|
||||||
P2->OUT &= ~0xC0; // off
|
P3->OUT &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // SLEEP pins low
|
||||||
P3->OUT &= ~0xC0; // low current sleep mode
|
P2->OUT &= ~(LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // EN pins low
|
||||||
}
|
}
|
||||||
|
|
||||||
// Drives both motors forward at duty (100 to 9900)
|
// Drives both motors forward at duty (100 to 9900)
|
||||||
// Runs for time duration, and then stops
|
// Runs for time duration, and then stops
|
||||||
// Stop the motors and return if any bumper switch is active
|
// Stop the motors and return if any bumper switch is active
|
||||||
void MotorForward(uint16_t duty, uint32_t times_10ms) {
|
void MotorForward(uint16_t duty, uint32_t times_10ms) {
|
||||||
// write this code
|
P5->OUT &= ~(LEFT_DIR_PIN | RIGHT_DIR_PIN); // set direction - PH low
|
||||||
|
P3->OUT |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // wake up motors
|
||||||
|
|
||||||
|
uint32_t i;
|
||||||
|
for (i = 0; i < times_10ms; ++i) {
|
||||||
|
P2->OUT |= (LEFT_PWM_PIN | RIGHT_PWM_PIN); // Enable both motors (EN high)
|
||||||
|
SysTickWait1us(duty);
|
||||||
|
|
||||||
|
P2->OUT &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN); // Disable motors
|
||||||
|
SysTickWait1us(10000 - duty);
|
||||||
|
|
||||||
|
uint8_t bump = BumpRead();
|
||||||
|
if (!(bump & BUMP_PINS)) break;
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Drives both motors backward at duty (100 to 9900)
|
// Drives both motors backward at duty (100 to 9900)
|
||||||
// Runs for time duration, and then stops
|
// Runs for time duration, and then stops
|
||||||
// Runs even if any bumper switch is active
|
// Runs even if any bumper switch is active
|
||||||
void MotorBackward(uint16_t duty, uint32_t times_10ms) {
|
void MotorBackward(uint16_t duty, uint32_t times_10ms) {
|
||||||
// write this code
|
P5->OUT |= (LEFT_DIR_PIN | RIGHT_DIR_PIN); // set direction - PH high
|
||||||
|
P3->OUT |= (LEFT_SLEEP_PIN | RIGHT_SLEEP_PIN); // wake up motors
|
||||||
|
|
||||||
|
uint32_t i;
|
||||||
|
for (i = 0; i < times_10ms; ++i) {
|
||||||
|
P2->OUT |= (LEFT_PWM_PIN | RIGHT_PWM_PIN); // Enable both motors (EN high)
|
||||||
|
SysTickWait1us(duty);
|
||||||
|
|
||||||
|
P2->OUT &= ~(LEFT_PWM_PIN | RIGHT_PWM_PIN); // Disable motors
|
||||||
|
SysTickWait1us(10000 - duty);
|
||||||
|
|
||||||
|
uint8_t bump = BumpRead();
|
||||||
|
if (!(bump & BUMP_PINS)) break;
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Drives just the left motor forward at duty (100 to 9900)
|
// Drives just the left motor forward at duty (100 to 9900)
|
||||||
|
@ -45,7 +123,22 @@ void MotorBackward(uint16_t duty, uint32_t times_10ms) {
|
||||||
// Runs for time duration, and then stops
|
// Runs for time duration, and then stops
|
||||||
// Stop the motor and return if any bumper switch is active
|
// Stop the motor and return if any bumper switch is active
|
||||||
void MotorLeft(uint16_t duty, uint32_t times_10ms) {
|
void MotorLeft(uint16_t duty, uint32_t times_10ms) {
|
||||||
// write this code
|
P5->OUT &= ~(LEFT_DIR_PIN); // set direction
|
||||||
|
P3->OUT |= (LEFT_SLEEP_PIN); // wake up motors
|
||||||
|
|
||||||
|
uint32_t i;
|
||||||
|
for (i = 0; i < times_10ms; ++i) {
|
||||||
|
P2->OUT |= (LEFT_PWM_PIN); // Enable both motors (EN high)
|
||||||
|
SysTickWait1us(duty);
|
||||||
|
|
||||||
|
P2->OUT &= ~(LEFT_PWM_PIN); // Disable motors
|
||||||
|
SysTickWait1us(10000 - duty);
|
||||||
|
|
||||||
|
uint8_t bump = BumpRead();
|
||||||
|
if (!(bump & BUMP_PINS)) break;
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Drives just the right motor forward at duty (100 to 9900)
|
// Drives just the right motor forward at duty (100 to 9900)
|
||||||
|
@ -53,5 +146,20 @@ void MotorLeft(uint16_t duty, uint32_t times_10ms) {
|
||||||
// Runs for time duration, and then stops
|
// Runs for time duration, and then stops
|
||||||
// Stop the motor and return if any bumper switch is active
|
// Stop the motor and return if any bumper switch is active
|
||||||
void MotorRight(uint16_t duty, uint32_t times_10ms) {
|
void MotorRight(uint16_t duty, uint32_t times_10ms) {
|
||||||
// write this code
|
P5->OUT &= ~(RIGHT_DIR_PIN); // set direction - PH high
|
||||||
|
P3->OUT |= (RIGHT_SLEEP_PIN); // wake up motors
|
||||||
|
|
||||||
|
uint32_t i;
|
||||||
|
for (i = 0; i < times_10ms; ++i) {
|
||||||
|
P2->OUT |= (RIGHT_PWM_PIN); // Enable both motors (EN high)
|
||||||
|
SysTickWait1us(duty);
|
||||||
|
|
||||||
|
P2->OUT &= ~(RIGHT_PWM_PIN); // Disable motors
|
||||||
|
SysTickWait1us(10000 - duty);
|
||||||
|
|
||||||
|
uint8_t bump = BumpRead();
|
||||||
|
if (!(bump & BUMP_PINS)) break;
|
||||||
|
}
|
||||||
|
|
||||||
|
MotorStop();
|
||||||
}
|
}
|
|
@ -9,10 +9,24 @@ void SysTickInit(void) {
|
||||||
|
|
||||||
// Assumes 48 MHz bus clock
|
// Assumes 48 MHz bus clock
|
||||||
void SysTickWait(uint32_t delay_ticks) {
|
void SysTickWait(uint32_t delay_ticks) {
|
||||||
// write this code
|
// 1. Write a desired delay_ticks value into the SysTick->LOAD register and subtract 1 from it,
|
||||||
|
SysTick->LOAD = delay_ticks - 1;
|
||||||
|
|
||||||
|
// 2. Clear the SysTick->VAL counter value, which also clears the COUNT bit,
|
||||||
|
SysTick->VAL = 0;
|
||||||
|
|
||||||
|
// 3. Wait for the COUNT bit in the SysTick->CTRL register to be set.
|
||||||
|
while((SysTick->CTRL & 0x00010000) == 0); // wait for COUNTFLAG
|
||||||
|
|
||||||
// any write to CVR clears it and COUNTFLAG in CSR
|
// any write to CVR clears it and COUNTFLAG in CSR
|
||||||
}
|
}
|
||||||
|
|
||||||
void SysTickWait1us(uint32_t times) {
|
void SysTickWait1us(uint32_t times) {
|
||||||
// write this code
|
uint32_t count = (48 * times) / 0x00FFFFFF;
|
||||||
|
uint32_t rem = (48 * times) % 0x00FFFFFF;
|
||||||
|
uint32_t i;
|
||||||
|
for (i = 0; i < count; ++i) {
|
||||||
|
SysTickWait(0x00FFFFFF); // wait max
|
||||||
|
}
|
||||||
|
SysTickWait(rem);
|
||||||
}
|
}
|
34
lab4/main.c
34
lab4/main.c
|
@ -44,16 +44,17 @@ void SwitchInit(void) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void WaitTouchRelease(void) {
|
void WaitTouchRelease(void) {
|
||||||
while(!(SW1IN || SW2IN)) {} // wait for touch
|
while(!(SW1IN || SW2IN)); // wait for touch
|
||||||
while(SW1IN || SW2IN) {} // wait for release
|
while( SW1IN || SW2IN ); // wait for release
|
||||||
}
|
}
|
||||||
|
|
||||||
int main_test_systick(void) {
|
int main_f(void) {
|
||||||
ClockInit48MHz();
|
ClockInit48MHz();
|
||||||
SysTickInit();
|
SysTickInit();
|
||||||
RedLEDInit();
|
RedLEDInit();
|
||||||
uint32_t H = 7500;
|
uint32_t H = 5000;
|
||||||
uint32_t L = 10000 - H;
|
uint32_t L = 10000 - H;
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
P1->OUT |= 0x01;
|
P1->OUT |= 0x01;
|
||||||
SysTickWait1us(H);
|
SysTickWait1us(H);
|
||||||
|
@ -66,20 +67,37 @@ int main_test_systick(void) {
|
||||||
// The heartbeat stops when the operator pushes Button 2
|
// The heartbeat stops when the operator pushes Button 2
|
||||||
// When beating, the P1.0 LED oscillates at 100 Hz (too fast to see with the eye)
|
// When beating, the P1.0 LED oscillates at 100 Hz (too fast to see with the eye)
|
||||||
// and the duty cycle is varied sinuosoidally once a second
|
// and the duty cycle is varied sinuosoidally once a second
|
||||||
int main_heartbeat(void) {
|
int main_s(void) {
|
||||||
|
uint32_t H;
|
||||||
|
uint32_t L;
|
||||||
|
uint32_t i = 0;
|
||||||
ClockInit48MHz();
|
ClockInit48MHz();
|
||||||
// write this code
|
SysTickInit();
|
||||||
|
RedLEDInit();
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
// write this code
|
H = pulse_us[i];
|
||||||
|
L = 10000 - H; // 2. calculate L
|
||||||
|
P1->OUT |= 0x01; // 3. set P1.0 high
|
||||||
|
SysTickWait1us(H); // 4. wait H us
|
||||||
|
P1->OUT &= ~0x01; // 5. clear P1.0 low
|
||||||
|
SysTickWait1us(L); // 6. Wait L us
|
||||||
|
i = (i + 1) % 100;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int main_test_wheels(void) {
|
|
||||||
|
void MotorTestPulse(void);
|
||||||
|
int main(void) {
|
||||||
ClockInit48MHz();
|
ClockInit48MHz();
|
||||||
SysTickInit();
|
SysTickInit();
|
||||||
SwitchInit();
|
SwitchInit();
|
||||||
BumpInit();
|
BumpInit();
|
||||||
MotorInit(); // your function
|
MotorInit(); // your function
|
||||||
|
|
||||||
|
MotorForward(1500, 100);
|
||||||
|
return 0;
|
||||||
|
|
||||||
while (true) {
|
while (true) {
|
||||||
WaitTouchRelease();
|
WaitTouchRelease();
|
||||||
MotorForward(1500, 100); // your function
|
MotorForward(1500, 100); // your function
|
||||||
|
|
Loading…
Reference in New Issue