Alex Liu
Published © GPL3+

Texas Instruments RSLK With MeArm - WiFi Controlled

Learn about creating a wirelessly controlled robot with the TI RSLK that can not only move around but grab objects with its arm.

AdvancedShowcase (no instructions)180
Texas Instruments RSLK With MeArm - WiFi Controlled

Things used in this project

Story

Read more

Code

Library Functions for Wheel and Arm

C/C++
#include "msp.h"
#include ".\Clock.h"
#include ".\LaunchPad.h"
#include ".\PWM.h"
#include ".\Motor.h"

//#include "main_RSLK.h"

int16_t joyX = 0;
int16_t joyY = 0;
int16_t leftWheelDuty = 0;
int16_t rightWheelDuty = 0;
// Array to hold mearm servo duty cycles
uint16_t servoDuty[4] = {2949, 2949, 2949, 2949};

/************************************** Arm Control Functions **************************************************/

//***************************PWM_Init12*******************************
// PWM outputs on P2.4, P2.5
// Inputs:  period (1.333us)
//          duty1
//          duty2
// Outputs: none
// SMCLK = 48MHz/4 = 12 MHz, 83.33ns
// Counter counts up to TA0CCR0 and back down
// Let Timerclock period T = 8/12MHz = 666.7ns
// P2.4=1 when timer equals TA0CCR1 on way down, P2.4=0 when timer equals TA0CCR1 on way up
// P2.5=1 when timer equals TA0CCR2 on way down, P2.5=0 when timer equals TA0CCR2 on way up
// Period of P2.4 is period*1.333us, duty cycle is duty1/period
// Period of P2.5 is period*1.333us, duty cycle is duty2/period
void PWM_Init_Servo(uint16_t period, uint16_t duty){
	// invalid input
	if(duty >= period) return;
	// bit  mode
	// 9-8  10    TASSEL, SMCLK=12MHz
	// 7-6  11    ID, divide by 2
	// 5-4  11    MC, up-down mode
	// 2    0     TACLR, no clear
	// 1    0     TAIE, no interrupt
	// 0          TAIFG*/
	P7->DIR |= 0xF0;          // P7.4 - P7.7 output
	P7->SEL0 |= 0xF0;         // P7.4 - P7.7 Timer1A functions
	P7->SEL1 &= ~0xF0;        // P7.4 - P7.7 Timer1A functions
	TIMER_A1->CCTL[0] = 0x0080;      // CCI0 toggle
	TIMER_A1->CCR[0] = period;       // Period is 2*period*8*83.33ns is 1.333*period
	TIMER_A1->EX0 = 0x0000;          //    divide by 1
	TIMER_A1->CCTL[3] = 0x0040;      // CCR3 toggle/reset
	TIMER_A1->CCR[3] = duty;         // CCR3 duty cycle is duty3/period
	TIMER_A1->CCTL[4] = 0x0040;      // CCR4 toggle/reset
	TIMER_A1->CCR[4] = duty;         // CCR4 duty cycle is duty4/period
	TIMER_A1->CCTL[1] = 0x0040;      // CCR1 toggle/reset
	TIMER_A1->CCR[1] = duty;         // CCR1 duty cycle is duty1/period
	TIMER_A1->CCTL[2] = 0x0040;      // CCR2 toggle/reset
	TIMER_A1->CCR[2] = duty;         // CCR2 duty cycle is duty2/period
	TIMER_A1->CTL = 0x0270;          // SMCLK=12MHz, divide by 2, up-down mode
}

//***************************PWM_Duty1*******************************
// change duty cycle of PWM output on P2.4
// Inputs:  duty1
// Outputs: none
// period of P2.4 is 2*period*666.7ns, duty cycle is duty1/period
void PWM_Duty_Servo(uint16_t * duty){
	if(duty[0] >= TIMER_A1->CCR[0]) return; // bad input
	if(duty[1] >= TIMER_A1->CCR[0]) return; // bad input
	if(duty[2] >= TIMER_A1->CCR[0]) return; // bad input
	if(duty[3] >= TIMER_A1->CCR[0]) return; // bad input
	TIMER_A1->CCR[1] = duty[0];             // CCR1 duty cycle is duty1/period
	TIMER_A1->CCR[2] = duty[1];             // CCR1 duty cycle is duty1/period
	TIMER_A1->CCR[3] = duty[2];             // CCR1 duty cycle is duty1/period
	TIMER_A1->CCR[4] = duty[3];             // CCR1 duty cycle is duty1/period
}

void changeServoDuty(int16_t joy, uint16_t servoIndex, uint16_t min, uint16_t max){
    if((servoDuty[servoIndex] < max) && (joy <= -2000)){servoDuty[servoIndex] += 10;}
    if((servoDuty[servoIndex] > min) && (joy >= 2000)){servoDuty[servoIndex] -= 10;}
}

void ServoCTRL_Base(void){
    // Change Base PWM
    changeServoDuty(joyX, 0, 1769, 7667);
}

void ServoCTRL_Height(void){
    // Change Height PWM
    changeServoDuty(joyY, 2, 1769, 5898);
}

void ServoCTRL_Length(void){
    // Change Length PWM
    changeServoDuty(joyY, 1, 2359, 7667);
}

void ServoCTRL_Claw(void){
    // Change Claw PWM
    changeServoDuty(joyX, 3, 2949, 7667);
}

void ServoMotor_Init(void){
    P7->SEL0 &= ~0b11110000;
    P7->SEL1 &= ~0b11110000;    // 1) configure P7.4-7 as GPIO
    P7->DIR |= 0b11110000;      // 2) make P7.4-7 output
    P7->OUT &= ~0b11110000;     // 3) output LOW
    PWM_Init_Servo(58982, 0);   // 50 Hz
}

void ServoMotor_Run(void){
    while(1){
        PWM_Duty_Servo(servoDuty);
    }
}

/* 
 * Function to control base and length servo for RTOS
 */
void Servo_BaseLength(){
	ServoCTRL_Base();
	ServoCTRL_Length();
	//PWM_Duty_Servo(servoDuty);
}

/* 
 * Function to control height and claw servo for RTOS
 */
void Servo_HeightClaw(){
	ServoCTRL_Height();
	ServoCTRL_Claw();
	//PWM_Duty_Servo(servoDuty);
}

/***************************************************************************************************************/

/************************************** Wheel Control Functions ************************************************/

// Actual Values:              -8000,-8000 right,up -8000,0 right 8000,8000 left,down  0,-8000 up -8000,8000 right,down  0,8000 down   8000,-8000 left,up  8000,0 left
// X and Y INV for Algorithm:   8000,8000 right,up   8000,0 right                                                                     -8000,8000 left,up  -8000,0 left
// Y INV for Algorithm:                                           8000,-8000 left,down 0,8000 up  -8000,-8000 right,down 0,-8000 down
void findWheelDuty(int16_t joyX, int16_t joyY, int16_t * leftDuty, int16_t * rightDuty){
    // manipulate joystick values for algorithm
	//     x and y directions for joystick are flipped from what algorithm needs
	//     additonal manipulation needed for handling backwards movement
	if ((joyX < 0 && joyY < 0) || (joyX > 0 && joyY < 0) || (joyX != 0 && joyY == 0)) {
		// (right,up), (right), (left,up), (left)
		// invert X and Y
		joyX*=-1;
		joyY*=-1;
	} else if ((joyX > 0 && joyY > 0) || (joyX < 0 && joyY > 0) || (joyX == 0 && joyY != 0)) {
		// (left,down), (up), (right,down), (down)
		// invert Y
		joyY*=-1;
	}
	// find percentage
    int16_t x = joyX / 80;
    int16_t y = joyY / 80;
    // Check for overflow
    if(x > 100){ x = 100;}
    if(x < -100){ x = -100;}
    if(y > 100){ y = 100;}
    if(y < -100){ y = -100;}
    // find x and y inverse
    int16_t x_inv = x * (-1);
    int16_t y_inv = y * (-1);
    // find absolute values
    int16_t x_abs = (x >= 0) ? x : x_inv;
    int16_t y_abs = (y >= 0) ? y : y_inv;
    // find V = Right + Left
    int16_t v = (100 - x_abs) * y / 100 + y;
    // find W = Right - Left
    int16_t w = (100 - y_abs) * x_inv / 100 + x_inv;
    // find Right and Left
    int16_t right = (v + w) / 2;
    int16_t left = (v - w) / 2;
    // scale back to Motor values, assuming 3000 is max
    *rightDuty = right * 30;
    *leftDuty = left * 30;
}

void Motor_Move(int16_t leftDuty, int16_t rightDuty){
    uint16_t leftPWM;
    uint16_t rightPWM;
    if(leftDuty < 0){
        // backward on left
        P5->OUT |= 0b00010000;
        leftPWM = (uint16_t)(leftDuty * (-1));
    }
    else{
        // forward on left
        P5->OUT &= ~0b00010000;
        leftPWM = (uint16_t)(leftDuty);
    }
    if(rightDuty < 0){
        // backward on right
        P5->OUT |= 0b00100000;
        rightPWM = (uint16_t)(rightDuty * (-1));
    }
    else{
        // forward on right
        P5->OUT &= ~0b00100000;
        rightPWM = (uint16_t)(rightDuty);
    }
    // Wake up motors
    P3->OUT |= 0xC0;
    // Pass in duty cycle
    PWM_Duty3(rightPWM);
    PWM_Duty4(leftPWM);
}

/***************************************************************************************************************/

void test(void){
    // Test Wheels
    joyX = 0;
    joyY = 8000;
    findWheelDuty(joyX, joyY, &leftWheelDuty, &rightWheelDuty);
    Motor_Move(leftWheelDuty, rightWheelDuty);
    joyX = -8000;
    joyY = 1000;
    findWheelDuty(joyX, joyY, &leftWheelDuty, &rightWheelDuty);
    Motor_Move(leftWheelDuty, rightWheelDuty);
    joyX = -4000;
    joyY = -2000;
    findWheelDuty(joyX, joyY, &leftWheelDuty, &rightWheelDuty);
    Motor_Move(leftWheelDuty, rightWheelDuty);
    Motor_Stop();
	
    // Test Arm
    while(1){
        joyX = 5000;
        joyY = 5000;
        while(servoDuty[0] < 7667){
            ServoCTRL_Base();
            ServoCTRL_Length();
            ServoCTRL_Height();
            ServoCTRL_Claw();
            PWM_Duty_Servo(servoDuty);
            int j;
            for(j = 0; j < 3000; j++);
        }
        joyX = -5000;
        joyY = -5000;
        while(servoDuty[0] > 1769){
            ServoCTRL_Base();
            ServoCTRL_Length();
            ServoCTRL_Height();
            ServoCTRL_Claw();
            PWM_Duty_Servo(servoDuty);
            int j;
            for(j = 0; j < 3000; j++);
        }
    }
}

/**
 * main.c
 */
void main_RSLK(void)
{
    WDT_A->CTL = WDT_A_CTL_PW | WDT_A_CTL_HOLD;     // stop watchdog timer

    Clock_Init48MHz();
    LaunchPad_Init();

    Motor_Init();
    ServoMotor_Init();
    test();
    while(1);
}

RTOS Threads Source

C/C++
#include "msp.h"
#include "driverlib.h"
#include "BSP.h"
#include "cc3100_usage.h"
#include "G8RTOS_Scheduler.h"
#include "G8RTOS_Semaphores.h"
#include "RSLKThreads.h"
#include <stdlib.h>
#include <time.h>
#include <stdbool.h>
#include <string.h>

extern int16_t joyX;
extern int16_t joyY;
extern int16_t leftWheelDuty;
extern int16_t rightWheelDuty;
extern uint16_t servoDuty[4];

// 0 for Wheels, 1 for Servo Base/Length, 2 for Servo Height/Claw
uint8_t mode = 0;

// Semaphores
semaphore_t joyMutex;
semaphore_t infoMutex;

HostInfo_t hostData;
ClientInfo_t clientData;

void vIdle(void){
    for(;;);
}

void vTaskReadJoy(void){

    for(;;){

        G8RTOS_WaitSemaphore(&joyMutex);

        GetJoystickCoordinates(&joyX, &joyY);
        //joyX *= -1;
        //joyY *= -1;
        if((joyX < 1000) && (joyX > -1000)){joyX = 0;}
        if((joyY < 1000) && (joyY > -1000)){joyY = 0;}

        if(mode == 2){
            // Height and Claw
            Servo_HeightClaw();
        }
        else if(mode == 1){
            // Base and Length
            Servo_BaseLength();
        }
        else{
            // Wheels
            findWheelDuty(joyX, joyY, &leftWheelDuty, &rightWheelDuty);
        }

        G8RTOS_SignalSemaphore(&joyMutex);

        OS_Sleep(5);
    }
}


void vTaskMoveWheels(void){

    for(;;){

        G8RTOS_WaitSemaphore(&joyMutex);

        Motor_Move(leftWheelDuty, rightWheelDuty);

        G8RTOS_SignalSemaphore(&joyMutex);

        OS_Sleep(5);
    }
}

void vTaskMoveServo(void){

    for(;;){

        G8RTOS_WaitSemaphore(&joyMutex);

        PWM_Duty_Servo(servoDuty);

        G8RTOS_SignalSemaphore(&joyMutex);

        OS_Sleep(5);
    }
}

void PORT4_IRQHandler(void){
    __NVIC_DisableIRQ(PORT4_IRQn);
    if((P4->IFG) & BIT5){
        P4->IE &= ~BIT5;
        P4->IFG &= ~BIT5;
        if(mode == 1){
            mode = 2;
        }
        else{
            mode = 1;
        }
        P4->IE |= BIT5;
    }
    else if((P4->IFG) & BIT4){
        P4->IE &= ~BIT4;
        P4->IFG &= ~BIT4;
        mode = 0;
        P4->IE |= BIT4;
    }
    else{
        P4->IFG &= ~(BIT4 | BIT5);
    }
    __NVIC_EnableIRQ(PORT4_IRQn);
}

void vHostSend(void){

    for(;;){

        // Fill packet for client
        G8RTOS_WaitSemaphore(&joyMutex);

        hostData = (HostInfo_t) {
            .IP_address   = RSLK_HOST_IP,
            .leftWheelDuty = leftWheelDuty,
            .rightWheelDuty = rightWheelDuty,
            .mode          = mode,
            .ready        = true,
        };
        memcpy(&hostData.servoDuty, &servoDuty, sizeof(hostData.servoDuty));

        G8RTOS_WaitSemaphore(&infoMutex);

        // Send packet
        SendData((uint8_t *)&hostData, RSLK_CLIENT_IP, sizeof(hostData));

        G8RTOS_SignalSemaphore(&infoMutex);
        G8RTOS_SignalSemaphore(&joyMutex);

        OS_Sleep(30);
    }
}

void vClientReceive(void){

    for(;;){

        int32_t retVal = -1;

        // Continually receive data until retVal >= 0 (meaning valid data has been read)
        while(!(retVal >= 0))
        {
            G8RTOS_WaitSemaphore(&infoMutex);
            retVal = ReceiveData((uint8_t *)&hostData, sizeof(hostData));
            G8RTOS_SignalSemaphore(&infoMutex);
            OS_Sleep(2);
        }

        // Empty the package
        G8RTOS_WaitSemaphore(&joyMutex);
        memcpy(&servoDuty, &hostData.servoDuty, sizeof(servoDuty));
        leftWheelDuty = hostData.leftWheelDuty;
        rightWheelDuty = hostData.rightWheelDuty;
        mode = hostData.mode;
        G8RTOS_SignalSemaphore(&joyMutex);

        // Sleep 5 ms
        OS_Sleep(3);
    }
}

int main_test_host(void){

    G8RTOS_Init(1);

    uartInit();

    P4->DIR &= ~(BIT4 | BIT5);
    P4->OUT |= BIT4 | BIT5; // Sets res to pull-up
    P4->REN |= BIT4 | BIT5; // Pull-up resistor
    P4->SEL0 = 0;
    P4->SEL1 = 0;
    P4->IES |= BIT4 | BIT5;  // High-to-low transition
    P4->IFG &= ~(BIT4 | BIT5); // P4.4 IFG cleared
    P4->IE |= BIT4 | BIT5; // Enable interrupt on P4.4

    NVIC_EnableIRQ(PORT4_IRQn);

    initCC3100(Client);
    uint32_t boardIP = getLocalIP();

    hostData = (HostInfo_t) {
        .IP_address   = RSLK_HOST_IP,
        .leftWheelDuty = leftWheelDuty,
        .rightWheelDuty = rightWheelDuty,
        .mode          = mode,
        .ready        = false,
    };
    memcpy(&hostData.servoDuty, &servoDuty, sizeof(hostData.servoDuty));

    clientData = (ClientInfo_t) {
        .IP_address   = RSLK_CLIENT_IP,
        .ready        = false,
    };

    // Send ready to client
    hostData.ready = true;
    SendData((uint8_t *)&hostData, RSLK_CLIENT_IP, sizeof(hostData));

    // Wait for acknowledge
    int32_t retVal = -1;
    while(!(retVal >= 0) || (clientData.ready == false))
    {
        retVal = ReceiveData((uint8_t *)&clientData, sizeof(clientData));
    }

    G8RTOS_InitSemaphore(&joyMutex, 1);
    G8RTOS_InitSemaphore(&infoMutex, 1);

    G8RTOS_AddThread(vTaskReadJoy, 5, "ReadJoy");
    G8RTOS_AddThread(vHostSend, 5, "HostSend");
    G8RTOS_AddThread(vIdle, 6, "Idle");

    G8RTOS_Launch();

    return 0;
}

int main_test_client(void){

    G8RTOS_Init(0);

    uartInit();

    Motor_Init();
    ServoMotor_Init();

    initCC3100(Client);
    uint32_t boardIP = getLocalIP();

    hostData = (HostInfo_t) {
        .IP_address   = RSLK_HOST_IP,
        .leftWheelDuty = 0,
        .rightWheelDuty = 0,
        .mode           = 0,
        .ready        = false,
    };
    memcpy(&hostData.servoDuty, &servoDuty, sizeof(hostData.servoDuty));

    clientData = (ClientInfo_t) {
        .IP_address   = RSLK_CLIENT_IP,
        .ready        = false,
    };

    // Wait for host
    int32_t retVal = -1;
    while(!(retVal >= 0) || (hostData.ready == false))
    {
        retVal = ReceiveData((uint8_t *)&hostData, sizeof(hostData));
    }

    // Send ready to host
    clientData.ready = true;
    SendData((uint8_t *)&clientData, RSLK_HOST_IP, sizeof(clientData));

    G8RTOS_InitSemaphore(&joyMutex, 1);
    G8RTOS_InitSemaphore(&infoMutex, 1);

    G8RTOS_AddThread(vTaskMoveWheels, 5, "Wheels");
    G8RTOS_AddThread(vTaskMoveServo, 5, "Servo");
    G8RTOS_AddThread(vClientReceive, 5, "ClientReceive");
    G8RTOS_AddThread(vIdle, 6, "Idle");

    G8RTOS_Launch();
}

RTOS Threads Header

C/C++
#ifndef RSLKTHREADS_H_
#define RSLKTHREADS_H_

#include <stdbool.h>
#include <stdint.h>

#define RSLK_HOST_IP    0xC0A8003B
#define RSLK_CLIENT_IP  0xC0A8005D
// host: C0A8003B (192.168.0.59), 3C (60), client: C0A8005D (192.168.0.93), 5E (94)
// computer: C0A80052 (192.168.0.82)

int main_test_host(void);
int main_test_client(void);
void vTaskReadJoy(void);
void vTaskMoveWheels(void);
void vTaskMoveServo(void);
void vIdle(void);

void vHostSend(void);
void vClientReceive(void);

//void button_int_PORT4(void);

typedef struct{
    uint32_t IP_address;
    int16_t leftWheelDuty;
    int16_t rightWheelDuty;
    uint16_t servoDuty[4];
    uint8_t mode;
    bool ready;
} HostInfo_t;

typedef struct{
    uint32_t IP_address;
    bool ready;
} ClientInfo_t;

#endif

main.c

C/C++
#include "msp.h"
#include <driverlib.h>
#include "G8RTOS_Scheduler.h"
#include "G8RTOS_Semaphores.h"
#include "RSLKThreads.h"

/* Configuration for UART */
static const eUSCI_UART_Config Uart115200Config = {
    EUSCI_A_UART_CLOCKSOURCE_SMCLK, // SMCLK Clock Source
    6, // BRDIV
    8, // UCxBRF
    0, // UCxBRS
    EUSCI_A_UART_NO_PARITY, // No Parity
    EUSCI_A_UART_LSB_FIRST, // LSB First
    EUSCI_A_UART_ONE_STOP_BIT, // One stop bit
    EUSCI_A_UART_MODE, // UART mode
    EUSCI_A_UART_OVERSAMPLING_BAUDRATE_GENERATION // Oversampling
};

void uartInit(){
    /* select the GPIO functionality */
    MAP_GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P1, GPIO_PIN2 | GPIO_PIN3, GPIO_PRIMARY_MODULE_FUNCTION);

    /* configure the digital oscillator */
    CS_setDCOCenteredFrequency(CS_DCO_FREQUENCY_12);

    /* configure the UART with baud rate 115200 */
    MAP_UART_initModule(EUSCI_A0_BASE, &Uart115200Config);

    /* enable the UART */
    MAP_UART_enableModule(EUSCI_A0_BASE);
}

//void PORT4_IRQHandler(void){
    //__NVIC_DisableIRQ(PORT4_IRQn);
    //P4->IE &= ~BIT0;

    // set interrupt flag
    //LCDTap();

    // All the following are done in WaitForTap()
    //P4->IFG &= ~BIT0; // must clear IFG flag, can also read PxIV to clear IFG
    //P4->IE |= BIT0;
    //__NVIC_EnableIRQ(PORT4_IRQn);
//}

/**
 * main.c
 */
void main(void)
{
	WDT_A->CTL = WDT_A_CTL_PW | WDT_A_CTL_HOLD;		// stop watchdog timer

	main_test_host();
	//main_test_client();
}

Credits

Alex Liu
1 project • 1 follower
Thanks to Xuanhao Shi.

Comments