EE445M RTOS
Taken at the University of Texas Spring 2015
motorpp.cpp
Go to the documentation of this file.
1 /* -*- mode: c++; c-basic-offset: 4; -*- */
2 #include "motorpp.hpp"
3 
4 #include "driverlib/sysctl.h"
5 #include "driverlib/pin_map.h"
6 #include "driverlib/pwm.h"
7 
8 #include "ctlsysctl.hpp"
9 #include "math.hpp"
10 
12 
14  memory_address_t pwm_base, memory_address_t pwm_gen,
15  memory_address_t pwm_out, bool motor_installed_backwards) {
16 
17  this->ctrl = blinker(ctrl_base, ctrl_pin);
18  this->ctrl_base = ctrl_base;
19  this->ctrl_pin = ctrl_pin;
20  this->pwm_base = pwm_base;
21  this->pwm_gen = pwm_gen;
22  this->pwm_out = pwm_out;
23 
24  ctlsys::enable_periph(ctrl_base);
25  ctlsys::enable_periph(pwm_base);
26 
27  this->motor_installed_backwards = motor_installed_backwards;
28 
29  enabled = false;
30 
31  motor_init();
32 }
33 
35 
36  this->motor_installed_backwards = backwards;
37 }
38 
40 
42  direction;
43 }
44 
45 void motor::stop() {
46 
47  if (direction == BACKWARD) {
48  set(100);
49  } else {
50  set(0);
51  }
52  enabled = false;
53  /* PWMGenDisable(pwm_base, pwm_gen); */
54 }
55 
56 void motor::set(percent_t speed, Direction dir) {
57 
58  this->direction = dir;
59  switch(adjusted_direction()) {
60  case FORWARD: ctrl.turn_off(ctrl_pin); break;
61  case BACKWARD: ctrl.turn_on(ctrl_pin); break;
62  default: while(1) {}
63  }
64  set(speed);
65 }
66 
67 void motor::set(percent_t speed) {
68 
69  speed = clamp(speed, 1, pwm_max_period);
70 
71  current_speed = speed;
72 
73  uint16_t adjusted_duty;
74  switch(adjusted_direction()) {
75  case FORWARD:
76  adjusted_duty = speed;
77  break;
78  case BACKWARD:
79  adjusted_duty = pwm_max_period - speed;
80  break;
81  default: while(1) {}
82  }
83 
84  if (enabled == true) {
85  PWMPulseWidthSet(pwm_base, pwm_out, speed);
86  }
87 }
88 
90 
92 
93  pwm_init();
94 }
95 
96 void motor::start() {
97 
98  enabled = true;
99  PWMGenEnable(pwm_base, pwm_gen);
100 }
101 
103 
104  uint32_t status = StartCritical();
105  /* nucleo: abstract */
106  ctlsys::enable_periph(GPIO_PORTB_BASE);
108 
109  SysCtlPWMClockSet(SYSCTL_PWMDIV_1);
110  PWMGenConfigure(pwm_base, pwm_gen, PWM_GEN_MODE_DOWN | PWM_GEN_MODE_NO_SYNC);
111  PWMGenPeriodSet(pwm_base, pwm_gen, DEFAULT_PWM_PERIOD);
112  PWMGenEnable(pwm_base, pwm_gen);
113 
114  switch(pwm_out) {
115  case PWM_OUT_0:
116  GPIOPinConfigure(GPIO_PB6_M0PWM0);
117  GPIOPinTypePWM(GPIO_PORTB_BASE, GPIO_PIN_6);
118  break;
119  case PWM_OUT_1:
120  GPIOPinConfigure(GPIO_PB7_M0PWM1);
121  GPIOPinTypePWM(GPIO_PORTB_BASE, GPIO_PIN_7);
122  break;
123  default:
124  while(1) {}
125  }
126 
127  /* Enable the outputs. */
128  PWMOutputState(pwm_base, (PWM_OUT_0_BIT | PWM_OUT_1_BIT), true);
129 
130  set(50, FORWARD);
131  start();
132  EndCritical(status);
133 }
134 
137 
139 }
140 
142 
143  return current_speed;
144 }
145 
146 /* Local Variables: */
147 /* firestarter: (compile "make -k -j32 -C ~/workspace/ee445m-labs/build/") */
148 /* End: */
percent_t current_speed
Definition: motorpp.hpp:34
void EndCritical(uint32_t primask)
Definition: criticalpp.hpp:14
uint32_t memory_address_t
Definition: adcpp.hpp:16
memory_address_t ctrl_base
Definition: motorpp.hpp:23
void motor_init(void)
Definition: motorpp.cpp:89
void set_motor_installed_backwards(bool)
Definition: motorpp.cpp:34
int32_t clamp(int32_t value, int32_t min, int32_t max)
Definition: math.cpp:5
uint32_t StartCritical(void)
Definition: criticalpp.hpp:9
Direction adjusted_direction(void)
Definition: motorpp.cpp:39
memory_address_t pwm_gen
Definition: motorpp.hpp:27
static const uint16_t pwm_max_period
Definition: motorpp.hpp:75
motor()
Definition: motorpp.cpp:11
blinker ctrl
Definition: motorpp.hpp:21
int32_t percent_t
Definition: motorpp.hpp:15
percent_t get(void)
Definition: motorpp.cpp:141
bool motor_installed_backwards
Definition: motorpp.hpp:29
Direction
Definition: direction.hpp:8
void start(void)
Definition: motorpp.cpp:96
#define DEFAULT_PWM_PERIOD
Definition: motorpp.hpp:17
void stop(void)
Definition: motorpp.cpp:45
void reverse(void)
Definition: motorpp.cpp:136
memory_address_t pwm_out
Definition: motorpp.hpp:28
bool enabled
Definition: motorpp.hpp:45
virtual void turn_off(pin_t pin)
Definition: blinker.cpp:30
memory_address_t ctrl_pin
Definition: motorpp.hpp:24
void set(percent_t speed)
Definition: motorpp.cpp:67
static Direction opposite(Direction d)
Definition: direction.hpp:12
void pwm_init(void)
Definition: motorpp.cpp:102
virtual void turn_on(pin_t pin)
Definition: blinker.cpp:26
Direction direction
Definition: motorpp.hpp:33
memory_address_t pwm_base
Definition: motorpp.hpp:25
static void enable_periph(uint32_t sys_periph)
Definition: ctlsysctl.hpp:24