Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Revision 0:ef6268629f0b, committed 2018-09-28
- Comitter:
- Reiko
- Date:
- Fri Sep 28 10:46:57 2018 +0000
- Child:
- 1:a286bf92d291
- Commit message:
- Firmware for UT Robotex 2018 basketball robot
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Motor/motor.cpp Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,147 @@
+#include "motor.h"
+
+Motor::Motor(PinName PWMpin, PinName dir1Pin, PinName dir2Pin, PinName encA, PinName encB)
+ : pwm(PWMpin), dir1(dir1Pin), dir2(dir2Pin), qed(encA, encB) {
+
+ pwmPeriod = 4000;
+ PwmOut pwm(PWMpin);
+ pwm.period_us(pwmPeriod);
+ setPoint = 0;
+ pMulti = 64;
+ iMulti = 2;
+ dMulti = 1;
+ error = 0;
+ prevError = 0;
+ P = 0;
+ I = 0;
+ minPwm = 100;
+ pidMulti = 256;
+ iMax = 4096 * pidMulti;
+
+ currentSpeed = 0;
+
+ currentPWM = 0;
+ stallCount = 0;
+ prevStallCount = 0;
+ stallWarningLimit = 60;
+ stallErrorLimit = 300;
+ stallLevel = 0;
+}
+
+void Motor::setPWM(int newPWM) {
+ currentPWM = newPWM;
+ if (newPWM < 0) {
+ pwm.pulsewidth_us(-1 * newPWM);
+ dir1 = 0;
+ dir2 = 1;
+ } else {
+ pwm.pulsewidth_us(newPWM);
+ dir1 = 1;
+ dir2 = 0;
+ }
+}
+
+int Motor::getSpeed() {
+ return currentSpeed;
+}
+
+int Motor::getDecoderCount() {
+ currentSpeed = qed.read();
+ return currentSpeed;
+}
+
+void Motor::setSpeed(int newSpeed) {
+ setPoint = newSpeed;
+
+ if (newSpeed == 0) {
+ resetPID();
+ }
+}
+
+void Motor::pid() {
+ prevError = error;
+ error = setPoint - getDecoderCount();
+
+ if (stallLevel != 2) {
+ float minPwmValue = minPwm;
+
+ if (setPoint == 0) {
+ minPwmValue = 0;
+ } else if (setPoint < 0) {
+ minPwmValue = -minPwm;
+ }
+
+ I += error * pidMulti * iMulti;
+ //constrain integral
+ if (I < -iMax) I = -iMax;
+ if (I > iMax) I = iMax;
+
+ //D = error - prevError;
+
+ int newPWMvalue = minPwmValue + error * pMulti + I / pidMulti;
+
+ //constrain pwm
+ if (newPWMvalue < -pwmPeriod) newPWMvalue = -pwmPeriod;
+ if (newPWMvalue > pwmPeriod) newPWMvalue = pwmPeriod;
+
+ prevStallCount = stallCount;
+ if ((currentSpeed < 5 && currentPWM == pwmPeriod || currentSpeed > -5 && currentPWM == -pwmPeriod) && stallCount < stallErrorLimit) {
+ stallCount++;
+ } else if (stallCount > 0) {
+ stallCount--;
+ }
+
+ setPWM(newPWMvalue);
+
+ if ((stallCount == stallWarningLimit - 1) && (prevStallCount == stallWarningLimit)) {
+ stallLevel = 0;
+ stallEndCallback.call();
+ stallChangeCallback.call();
+ } else if ((stallCount == stallWarningLimit) && (prevStallCount == stallWarningLimit - 1)) {
+ stallLevel = 1;
+ stallWarningCallback.call();
+ stallChangeCallback.call();
+ } else if (stallCount == stallErrorLimit) {
+ stallLevel = 2;
+ stallErrorCallback.call();
+ stallChangeCallback.call();
+ resetPID();
+ }
+ } else {
+ stallCount--;
+ if (stallCount == 0) {
+ stallLevel = 0;
+ stallEndCallback.call();
+ stallChangeCallback.call();
+ }
+ }
+}
+
+void Motor::resetPID() {
+ error = 0;
+ prevError = 0;
+ P = 0;
+ I = 0;
+ setPoint = 0;
+ setPWM(0);
+}
+
+int Motor::getStallLevel() {
+ return stallLevel;
+}
+
+void Motor::stallChange(void (*function)(void)) {
+ stallChangeCallback.attach(function);
+}
+
+void Motor::stallEnd(void (*function)(void)) {
+ stallEndCallback.attach(function);
+}
+
+void Motor::stallWarning(void (*function)(void)) {
+ stallWarningCallback.attach(function);
+}
+
+void Motor::stallError(void (*function)(void)) {
+ stallErrorCallback.attach(function);
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Motor/motor.h Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,110 @@
+#ifndef MOTOR_H
+#define MOTOR_H
+
+#include "mbed.h"
+#include "qed.h"
+
+class Motor {
+protected:
+ FunctionPointer stallChangeCallback;
+ FunctionPointer stallEndCallback;
+ FunctionPointer stallWarningCallback;
+ FunctionPointer stallErrorCallback;
+public:
+ /** Create an instance of the motor connected to specfied pins, and IO-expander.
+ *
+ * @param PWMpin Pin for PWM output
+ * @param dir1 Direction 1 pin
+ * @param dir2 Direction 2 pin
+ * @param encA Encoder pin
+ * @param encB Encoder pin
+ */
+ Motor(PinName PWMpin, PinName dir1Pin, PinName dir2Pin, PinName encA, PinName encB);
+
+ /** Set speed setpoint
+ *
+ * @param newSpeed New setpoint
+ */
+ void setSpeed(int newSpeed);
+
+ /** Get current speed setpoint value */
+ int getSpeed();
+
+ /**Method that calculates appropriate PWM values for keeping motor speed close to setpoint
+ * This method shoud be called periodically (60Hz)
+ */
+ void pid();
+
+ int getStallLevel();
+
+ void stallChange(void (*function)(void));
+
+ template<typename T>
+ void stallChange(T *object, void (T::*member)(void)) {
+ stallChangeCallback.attach(object, member);
+ }
+
+ void stallEnd(void (*function)(void));
+
+ template<typename T>
+ void stallEnd(T *object, void (T::*member)(void)) {
+ stallEndCallback.attach(object, member);
+ }
+
+ void stallWarning(void (*function)(void));
+
+ template<typename T>
+ void stallWarning(T *object, void (T::*member)(void)) {
+ stallWarningCallback.attach(object, member);
+ }
+
+ void stallError(void (*function)(void));
+
+ template<typename T>
+ void stallError(T *object, void (T::*member)(void)) {
+ stallErrorCallback.attach(object, member);
+ }
+
+private:
+ PwmOut pwm;
+ DigitalOut dir1;
+ DigitalOut dir2;
+ QED qed;
+
+ int currentSpeed;
+ int getDecoderCount();
+
+ void resetPID();
+
+ /** Set pwm duty cycle
+ *
+ * @param newPWM Duty cycle
+ */
+ void setPWM(int newPWM);
+
+ //void pid();
+
+ int setPoint;
+ int pMulti;
+ int iMulti;
+ int dMulti;
+ int error;
+ int prevError;
+ int P;
+ int I;
+ int D;
+ int minPwm;
+ int pidMulti;
+ int iMax;
+
+ int pwmPeriod;
+
+ int currentPWM;
+ int stallCount;
+ int prevStallCount;
+ int stallWarningLimit;
+ int stallErrorLimit;
+ int stallLevel;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/QED/qed.cpp Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,33 @@
+#include "qed.h"
+
+QED::QED(PinName channelA, PinName channelB)
+ : interruptA(channelA), interruptB(channelB) {
+
+ pulses = 0;
+ currState = (interruptA.read() << 1) | (interruptB.read());
+ prevState = currState;
+
+ interruptA.rise(this, &QED::decode);
+ interruptA.fall(this, &QED::decode);
+ interruptB.rise(this, &QED::decode);
+ interruptB.fall(this, &QED::decode);
+}
+
+int QED::read() {
+ int pulseCount = pulses;
+ pulses = 0;
+ return pulseCount;
+}
+
+void QED::decode() {
+ currState = (interruptA.read() << 1) | (interruptB.read());
+
+ int change = (prevState & PREV_MASK) ^ ((currState & CURR_MASK) >> 1);
+
+ if (change == 0) {
+ change = -1;
+ }
+
+ pulses -= change;
+ prevState = currState;
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/QED/qed.h Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,28 @@
+#ifndef QED_H
+#define QED_H
+
+#include "mbed.h"
+
+#define PREV_MASK 0x1 //Mask for the previous state in determining direction of rotation.
+#define CURR_MASK 0x2 //Mask for the current state in determining direction of rotation.
+#define INVALID 0x3 //XORing two states where both bits have changed.
+
+class QED {
+public:
+ QED(PinName channelA, PinName channelB);
+
+ int read();
+
+private:
+ void decode();
+
+ InterruptIn interruptA;
+ InterruptIn interruptB;
+
+ volatile int pulses;
+
+ int prevState;
+ int currState;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/RFManager/CircularBuffer2.h Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,74 @@
+/* Copyright (c) 2010-2011 mbed.org, MIT License
+*
+* Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+* and associated documentation files (the "Software"), to deal in the Software without
+* restriction, including without limitation the rights to use, copy, modify, merge, publish,
+* distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the
+* Software is furnished to do so, subject to the following conditions:
+*
+* The above copyright notice and this permission notice shall be included in all copies or
+* substantial portions of the Software.
+*
+* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+* BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+* DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+*/
+
+#ifndef CIRCULARBUFFER2_H
+#define CIRCULARBUFFER2_H
+
+template <class T>
+class CircularBuffer2 {
+public:
+
+ CircularBuffer2(int length) {
+ write = 0;
+ read = 0;
+ size = length + 1;
+ buf = (T *)malloc(size * sizeof(T));
+ };
+
+ ~CircularBuffer2() {
+ free(buf);
+ }
+
+ bool isFull() {
+ return ((write + 1) % size == read);
+ };
+
+ bool isEmpty() {
+ return (read == write);
+ };
+
+ void queue(T k) {
+ if (isFull()) {
+ read++;
+ read %= size;
+ }
+ buf[write++] = k;
+ write %= size;
+ }
+
+ uint16_t available() {
+ return (write >= read) ? write - read : size - read + write;
+ };
+
+ bool dequeue(T * c) {
+ bool empty = isEmpty();
+ if (!empty) {
+ *c = buf[read++];
+ read %= size;
+ }
+ return(!empty);
+ };
+
+private:
+ volatile uint16_t write;
+ volatile uint16_t read;
+ uint16_t size;
+ T * buf;
+};
+
+#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/RFManager/RFManager.cpp Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,156 @@
+//#include <TARGET_LPC1768/cmsis.h>
+#include "RFManager.h"
+
+RFManager::RFManager(PinName txPinName, PinName rxPinName):
+ serial(txPinName, rxPinName), buf(64) {
+
+ messageAvailable = false;
+ receiveCounter = 0;
+ shortCommandsEnabled = false;
+ shortCommandLength = 5;
+ longCommandLength = 12;
+ commandLength = longCommandLength;
+
+ if (rxPinName == P2_1) {
+ serialId = 1;
+ } else if (rxPinName == P0_11) {
+ serialId = 2;
+ } else if (rxPinName == P0_1) {
+ serialId = 3;
+ } else {
+ serialId = 0;
+ }
+
+ serial.attach(this, &RFManager::rxHandler);
+}
+
+void RFManager::baud(int baudrate) {
+ serial.baud(baudrate);
+}
+
+void RFManager::rxHandler(void) {
+ // Interrupt does not work with RTOS when using standard functions (getc, putc)
+ // https://developer.mbed.org/forum/bugs-suggestions/topic/4217/
+
+ while (serial.readable()) {
+ char c = serialReadChar();
+
+ if (receiveCounter < commandLength) {
+ if (receiveCounter == 0) {
+ // Do not continue before a is received
+ if (c == 'a') {
+ receiveBuffer[receiveCounter] = c;
+ receiveCounter++;
+ }
+ } else if (c == 'a' && !shortCommandsEnabled
+ || c == 'a' && shortCommandsEnabled && (receiveCounter < commandLength - 1)
+ ) {
+ // If a is received in the middle, assume some bytes got lost before and start from beginning
+ receiveCounter = 0;
+
+ receiveBuffer[receiveCounter] = c;
+ receiveCounter++;
+ } else {
+ receiveBuffer[receiveCounter] = c;
+ receiveCounter++;
+ }
+
+ if (receiveCounter == commandLength) {
+ receiveCounter = 0;
+
+ for (unsigned int i = 0; i < commandLength; i++) {
+ buf.queue(receiveBuffer[i]);
+ }
+
+ if (!messageAvailable) {
+ handleMessage();
+ //break;
+ }
+ }
+ }
+ }
+}
+
+bool RFManager::readable() {
+ return messageAvailable;
+}
+
+char *RFManager::read() {
+ messageAvailable = false;
+ return receivedMessage;
+}
+
+void RFManager::send(char *sendData) {
+ serialWrite(sendData, commandLength);
+}
+
+void RFManager::send(char *sendData, int length) {
+ serialWrite(sendData, length);
+}
+
+void RFManager::update() {
+ /*if (receiveCounter == commandLength) {
+ handleMessage();
+ _callback.call();
+ }*/
+
+ if (buf.available() >= commandLength) {
+ handleMessage();
+ }
+}
+
+void RFManager::handleMessage() {
+ if (messageAvailable) {
+ return;
+ }
+
+ for (unsigned int i = 0; i < commandLength; i++) {
+ buf.dequeue(receivedMessage + i);
+ }
+
+ receivedMessage[commandLength] = '\0';
+
+ /*receiveCounter = 0;
+
+ memcpy(receivedMessage, receiveBuffer, sizeof(receiveBuffer));*/
+
+ messageAvailable = true;
+}
+
+void RFManager::serialWrite(char *sendData, int length) {
+ int i = 0;
+
+ while (i < length) {
+ if (serial.writeable()) {
+ serial.putc(sendData[i]);
+ }
+ i++;
+ }
+}
+
+char RFManager::serialReadChar() {
+ if (serialId == 1) {
+ return LPC_UART1->RBR;
+ }
+
+ if (serialId == 2) {
+ return LPC_UART2->RBR;
+ }
+
+ if (serialId == 3) {
+ return LPC_UART3->RBR;
+ }
+
+ return LPC_UART0->RBR;
+}
+
+void RFManager::setShortCommandMode(bool isEnabled) {
+ shortCommandsEnabled = isEnabled;
+ receiveCounter = 0;
+
+ if (isEnabled) {
+ commandLength = shortCommandLength;
+ } else {
+ commandLength = longCommandLength;
+ }
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/RFManager/RFManager.h Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,65 @@
+#ifndef RFMANAGER_H
+#define RFMANAGER_H
+
+#include "mbed.h"
+#include "CircularBuffer2.h"
+
+class RFManager {
+protected:
+ FunctionPointer _callback;
+
+public:
+ RFManager(PinName txPinName, PinName rxPinName);
+
+ void baud(int baudrate);
+
+ char *read();
+
+ void send(char *sendData);
+
+ void send(char *sendData, int length);
+
+ void update();
+
+ void handleMessage();
+
+ void setShortCommandMode(bool isEnabled);
+
+ bool readable();
+
+ void attach(void (*function)(void)) {
+ _callback.attach(function);
+ }
+
+ template<typename T>
+ void attach(T *object, void (T::*member)(void)) {
+ _callback.attach( object, member );
+ }
+
+private:
+ Serial serial;
+
+ int serialId;
+
+ void rxHandler(void);
+
+ bool messageAvailable;
+
+ void serialWrite(char *sendData, int length);
+ char serialReadChar();
+
+ CircularBuffer2<char> buf;
+
+ unsigned int receiveCounter;
+ char receiveBuffer[16];
+
+ char receivedMessage[16];
+
+ bool shortCommandsEnabled;
+ unsigned int commandLength;
+ unsigned int shortCommandLength;
+ unsigned int longCommandLength;
+};
+
+
+#endif //RFManager_H
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/USBDevice.lib Fri Sep 28 10:46:57 2018 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/mbed_official/code/USBDevice/#53949e6131f6
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp Fri Sep 28 10:46:57 2018 +0000
@@ -0,0 +1,143 @@
+#include "mbed.h"
+#include "pins.h"
+#include "motor.h"
+#include "USBSerial.h"
+#include "RFManager.h"
+
+USBSerial serial;
+
+Serial pc(USBTX, USBRX);
+
+DigitalOut led1(LED_1);
+DigitalOut led2(LED_2);
+DigitalOut led3(LED_3);
+
+static const int NUMBER_OF_MOTORS = 3;
+
+PwmOut m3(M3_PWM);
+
+Motor motor0(M0_PWM, M0_DIR1, M0_DIR2, M0_ENCA, M0_ENCB);
+Motor motor1(M1_PWM, M1_DIR1, M1_DIR2, M1_ENCA, M1_ENCB);
+Motor motor2(M2_PWM, M2_DIR1, M2_DIR2, M2_ENCA, M2_ENCB);
+//Motor motor3(M3_PWM, M3_DIR1, M3_DIR2, M3_ENCA, M3_ENCB);
+
+Motor * motors[NUMBER_OF_MOTORS] = {
+ &motor0, &motor1, &motor2
+};
+
+RFManager rfModule(COM1_TX, COM1_RX);
+
+void serialInterrupt();
+void parseCommand(char *command);
+
+Ticker pidTicker;
+unsigned int pidTickerCount = 0;
+static const float PID_FREQ = 60;
+
+char buf[32];
+int serialCount = 0;
+bool serialData = false;
+
+bool failSafeEnabled = true;
+int failSafeCount = 0;
+int failSafeLimit = 60;
+
+void pidTick() {
+ for (int i = 0; i < NUMBER_OF_MOTORS; i++) {
+ motors[i]->pid();
+ }
+
+ if (pidTickerCount++ % 60 == 0) {
+ led1 = !led1;
+ }
+
+ failSafeCount++;
+
+ if (failSafeCount == failSafeLimit) {
+ failSafeCount = 0;
+
+ if (failSafeEnabled) {
+ for (int i = 0; i < NUMBER_OF_MOTORS; ++i) {
+ motors[i]->setSpeed(0);
+ }
+
+ m3.pulsewidth_us(800);
+ }
+ }
+}
+
+int main() {
+ pidTicker.attach(pidTick, 1 / PID_FREQ);
+ //serial.attach(&serialInterrupt);
+
+ // Dribbler motor
+ //m3.period_us(4000);
+ m3.pulsewidth_us(800);
+
+ while (1) {
+ if (rfModule.readable()) {
+ serial.printf("<ref:%s>\n", rfModule.read());
+ }
+
+ rfModule.update();
+
+ if (serial.readable()) {
+ buf[serialCount] = serial.getc();
+
+ if (buf[serialCount] == '\n') {
+ parseCommand(buf);
+ serialCount = 0;
+ memset(buf, 0, 32);
+ } else {
+ serialCount++;
+ }
+ }
+ }
+}
+
+void parseCommand(char *buffer) {
+ failSafeCount = 0;
+
+ char *cmd = strtok(buffer, ":");
+
+ // buffer == "sd:14:16:10:30"
+ if (strncmp(cmd, "sd", 2) == 0) {
+ for (int i = 0; i < NUMBER_OF_MOTORS; ++i) {
+ motors[i]->setSpeed(atoi(strtok(NULL, ":")));
+ }
+
+ serial.printf("<gs:%d:%d:%d>\n",
+ motors[0]->getSpeed(),
+ motors[1]->getSpeed(),
+ motors[2]->getSpeed()
+ );
+ }
+
+ if (strncmp(cmd, "d", 1) == 0) {
+ int pulsewidth = atoi(buffer + 2);
+
+ if (pulsewidth < 800) {
+ pulsewidth = 800;
+ } else if (pulsewidth > 2100) {
+ pulsewidth = 2100;
+ }
+
+ m3.pulsewidth_us(pulsewidth);
+ }
+
+ if (strncmp(cmd, "gs", 2) == 0) {
+ serial.printf("<gs:%d:%d:%d>\n",
+ motors[0]->getSpeed(),
+ motors[1]->getSpeed(),
+ motors[2]->getSpeed()
+ );
+ }
+
+ if (strncmp(cmd, "rf", 2) == 0) {
+ rfModule.send(buffer + 3);
+ }
+
+ if (strncmp(cmd, "fs", 1) == 0) {
+ failSafeEnabled = buffer[3] != '0';
+ }
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Fri Sep 28 10:46:57 2018 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/mbed_official/code/mbed/builds/e95d10626187 \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/pins.h Fri Sep 28 10:46:57 2018 +0000 @@ -0,0 +1,58 @@ +#ifndef PINS_H_ +#define PINS_H_ +#include "mbed.h" + +// MOTOR0 (J1) +#define M0_PWM P2_0 +#define M0_DIR1 P4_29 +#define M0_DIR2 P4_28 +#define M0_ENCA P0_7 +#define M0_ENCB P0_6 + +// MOTOR1 (J4) +#define M1_PWM P2_1 +#define M1_DIR1 P0_9 +#define M1_DIR2 P0_8 +#define M1_ENCA P2_6 +#define M1_ENCB P2_7 + +// MOTOR2 (J5) +#define M2_PWM P2_2 +#define M2_DIR1 P0_15 +#define M2_DIR2 P0_16 +#define M2_ENCA P0_17 +#define M2_ENCB P0_18 + +// MOTOR3 (J6) +#define M3_PWM P2_3 +#define M3_DIR1 P0_19 +#define M3_DIR2 P0_20 +#define M3_ENCA P0_21 +#define M3_ENCB P0_22 + +// LEDS +#define LED_1 P1_18 +#define LED_2 P1_19 +#define LED_3 P1_22 + +// COM1 (J9) +#define COM1_TX P0_0 +#define COM1_RX P0_1 + +// COM2 (J11) +#define COM2_TX P0_10 +#define COM2_RX P0_11 + +// SPI (J10) +#define SPI_MOSI P1_24 +#define SPI_MISO P1_23 +#define SPI_SSEL P1_21 +#define SPI_SCK P1_20 + +// ISOLATED_IO (J8) +#define ISO_PWM5 P2_4 +#define ISO_PWM6 P2_5 +#define ISO_OUT P0_4 +#define ISO_IN P0_5 + +#endif