Ashok R
Published

NXP Scarab Robot

A Robot designed for Automate our routine tasks with smartness.

AdvancedShowcase (no instructions)Over 1 day1,966

Things used in this project

Hardware components

Kinetis Freedom Board with FlexIO
NXP Kinetis Freedom Board with FlexIO
×1
NXP NTAG I2C Plus Flex Antenna
×1
OV7670 - Camera Module
×1
Dual H-Bridge motor drivers L293D
Texas Instruments Dual H-Bridge motor drivers L293D
×1
HC-05 Bluetooth Module
HC-05 Bluetooth Module
×1
LED (generic)
LED (generic)
×2

Software apps and online services

Kinetis Design Studio (IDE)

Story

Read more

Schematics

Schematic

Code

Code for K82F

C/C++
#include <stdbool.h>
#include <stdio.h>
#include <stdlib.h>
#include "flexio_ov7670.h"
#include "fsl_device_registers.h"
#include "fsl_debug_console.h"
#include "board.h"
#include "math.h"
#include "fsl_i2c.h"
#include "fsl_fxos.h"
#include "fsl_port.h"
#include "pin_mux.h"
#include "clock_config.h"
#include "fsl_lpuart.h"
#include "flexio_ov7670.h"
#include "qflash.h"
#include "ntag.h"
#include "i2c.h"
#include "fsl_ftm.h"

#define BOARD_RLED_GPIO BOARD_LED_RED_GPIO
#define BOARD_RLED_GPIO_PIN BOARD_LED_RED_GPIO_PIN

#define BOARD_GLED_GPIO BOARD_LED_GREEN_GPIO
#define BOARD_GLED_GPIO_PIN BOARD_LED_GREEN_GPIO_PIN

#define BOARD_BLED_GPIO BOARD_LED_BLUE_GPIO
#define BOARD_BLED_GPIO_PIN BOARD_LED_BLUE_GPIO_PIN

#define DEMO_LPUART LPUART1
#define DEMO_LPUART_CLKSRC kCLOCK_Osc0ErClk
#define ECHO_BUFFER_LENGTH 8

/* The Flextimer instance/channel used for board */
#define BOARD_FTM_BASEADDR FTM3
#define BOARD_FIRST_FTM_CHANNEL 2U
#define BOARD_SECOND_FTM_CHANNEL 3U

/* Get source clock for FTM driver */
#define FTM_SOURCE_CLOCK CLOCK_GetFreq(kCLOCK_BusClk)

#define MOTOR1_A 1U
#define MOTOR1_B 3U
#define MOTOR2_A 2U
#define MOTOR2_B 4U
#define LIGHT_LED 5U

#define TASK_TIME 10

extern void FLEXIO_Ov7670AsynCallback(void);

void move_left();
void move_right();
void stop();
void move_forward();
void run_scarab();
void transfer_image();
void run_task();
void delay_ms(int dly);
/*!
 * @brief Release I2C bus
 *
 */
void BOARD_I2C_ReleaseBus(void);

/* LPUART user callback */
void LPUART_UserCallback(LPUART_Type *base, lpuart_handle_t *handle, status_t status, void *userData);

uint8_t ch1_wkey[] = "REN0SEZYDCCP9Q0A";
uint8_t ch1_rkey[] = "O6CT79WHV3HO3DZW";
uint8_t esp_mux_en[] = "AT+CIPMUX=1\r\n";
uint8_t esp_connect[] = "AT+CIPSTART=1,\"TCP\",\"184.106.153.149\",80\r\n";
uint8_t esp_set_length[] = "AT+CIPSEND=1,56\r\n";
uint8_t esp_send_data[] = "GET /update?key=REN0SEZYDCCP9Q0A&field1=000000\r\n";
uint8_t esp_clear_data[] = "DELETE /channels/131534/feeds.json?key=D73U8I5DB5LO01HV\r\n";

uint8_t g_rxBuffer[64] = {0};

/*******************************************************************************
 * Variables
 ******************************************************************************/


uint8_t ntag_header[16];
uint8_t ntag_path[128];

bool IsMoving = false;

extern i2c_master_handle_t g_m_handle;
/* FXOS device address */
const uint8_t g_accel_address[] = {0x1CU, 0x1DU, 0x1EU, 0x1FU};

uint8_t turn_plus=0;


int16_t xData = 0;
int16_t yData = 0;
int16_t xAngle = 0;
int16_t yAngle = 0;
int16_t pxAngle = 0;
int16_t pyAngle = 0;

lpuart_handle_t g_lpuartHandle;

uint8_t string_scarab_idle[] = "Scarab is Idle \r\n";
uint8_t string_scarab_active[] = "Scarab is Active \r\n";
uint8_t string_scarab_locked[] = "Scarab is Locked \r\n";
uint8_t string_LF[] = "\r\n";

uint8_t g_txString2[] = {'0','1','2','3','4','5','6','7','8','9'};
extern volatile uint8_t g_FlexioCameraFrameBuffer[OV7670_FRAME_BYTES];


/* Whether the SW button is pressed */
volatile bool module_enable = false;


volatile bool rxBufferEmpty = true;
volatile bool txBufferFull = false;
volatile bool txOnGoing = false;
volatile bool rxOnGoing = false;
volatile bool lights_on = false;
extern volatile bool flashOnGoing = false;
extern volatile bool isFinished = false;
uint8_t g_txBuffer[1024] = {0};
    /*******************************************************************************
     * Code
     ******************************************************************************/

    void PORTB_IRQHandler(void)
    {
        /* Clear the interrupt flag for PTB2 */
        PORT_ClearPinsInterruptFlags(PORTB, 1U << BOARD_FLEXIO_VSYNC_PIN_INDEX);
        FLEXIO_Ov7670AsynCallback();
    }


    /* LPUART user callback */
    void LPUART_UserCallback(LPUART_Type *base, lpuart_handle_t *handle, status_t status, void *userData)
    {
        userData = userData;

        if (kStatus_LPUART_TxIdle == status)
        {
            txBufferFull = false;
            txOnGoing = false;
        }

        if (kStatus_LPUART_RxIdle == status)
        {
            rxBufferEmpty = false;
            rxOnGoing = false;
        }
    }

    /* Delay n ms */
    void DelayMs(uint8_t n)
    {
        SysTick->CTRL |= SysTick_CTRL_CLKSOURCE_Msk;                      /* use core clock */
        SysTick->CTRL &= ~SysTick_CTRL_TICKINT_Msk;                       /* disable interrupt */
        SysTick->LOAD = n * ((CLOCK_GetFreq(kCLOCK_CoreSysClk)) / 1000U); /* n ms */
        SysTick->VAL = 0U;                                                /* clear COUNTFLAG */

        SysTick->CTRL |= SysTick_CTRL_ENABLE_Msk;

        /* wait for timeout */
        while (0U == (SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk))
        {
        }

        SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
    }

    uint32_t write_status=0;
      lpuart_transfer_t xfer;
int main(void) {

    uint32_t i,j;
    uint8_t regResult = 0;
    uint8_t array_addr_size = 0;

    lpuart_config_t config;


    gpio_pin_config_t cam_pinConfig;



    ftm_config_t ftmInfo;
    uint8_t updatedDutycycle = 0U;
    ftm_chnl_pwm_signal_param_t ftmParam[2];

    /* Configure ftm params with frequency 24kHZ */
    ftmParam[0].chnlNumber = (ftm_chnl_t)BOARD_FIRST_FTM_CHANNEL;
    ftmParam[0].level = kFTM_LowTrue;
    ftmParam[0].dutyCyclePercent = 0U;
    ftmParam[0].firstEdgeDelayPercent = 0U;

    ftmParam[1].chnlNumber = (ftm_chnl_t)BOARD_SECOND_FTM_CHANNEL;
    ftmParam[1].level = kFTM_LowTrue;
    ftmParam[1].dutyCyclePercent = 0U;
    ftmParam[1].firstEdgeDelayPercent = 0U;


    /* Define the init structure for the output LED pin */
    gpio_pin_config_t led_config = {
        kGPIO_DigitalOutput, 0,
    };

  BOARD_InitPins();
  BOARD_BootClockRUN();
  BOARD_InitDebugConsole();


  CLOCK_SetClkOutClock(0x06);

#if 1
    /* Init output LED GPIO. */
 // GPIO_PinInit(BOARD_RLED_GPIO, BOARD_RLED_GPIO_PIN, &led_config);
  GPIO_PinInit(BOARD_GLED_GPIO, BOARD_GLED_GPIO_PIN, &led_config);
  GPIO_PinInit(BOARD_BLED_GPIO, BOARD_BLED_GPIO_PIN, &led_config);
#endif



#if 1
    /* Init output MOTOR GPIO. */
  GPIO_PinInit(BOARD_MOTOR_GPIO, MOTOR1_A, &led_config);
  //GPIO_PinInit(BOARD_MOTOR_GPIO, MOTOR1_B, &led_config);
  //GPIO_PinInit(BOARD_MOTOR_GPIO, MOTOR2_A, &led_config);
  GPIO_PinInit(BOARD_MOTOR_GPIO, MOTOR2_B, &led_config);
  GPIO_PinInit(BOARD_LIGHT_GPIO, LIGHT_LED, &led_config);
#endif


#if 1

  /* enable OV7670 Reset output */
        cam_pinConfig.pinDirection = kGPIO_DigitalOutput;
        cam_pinConfig.outputLogic = 1U;

     GPIO_PinInit(GPIOC, 8U, &cam_pinConfig);
#endif
     LPUART_GetDefaultConfig(&config);
     config.enableTx = true;
     config.enableRx = true;
     LPUART_Init(DEMO_LPUART, &config, CLOCK_GetFreq(DEMO_LPUART_CLKSRC));
     LPUART_TransferCreateHandle(DEMO_LPUART, &g_lpuartHandle, LPUART_UserCallback, NULL);



     FTM_GetDefaultConfig(&ftmInfo);
        /* Initialize FTM module */
        FTM_Init(BOARD_FTM_BASEADDR, &ftmInfo);

        FTM_SetupPwm(BOARD_FTM_BASEADDR, ftmParam, 2U, kFTM_EdgeAlignedPwm, 24000U, FTM_SOURCE_CLOCK);
        FTM_StartTimer(BOARD_FTM_BASEADDR, kFTM_SystemClock);


        /* Start PWM mode with updated duty cycle */
        FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)BOARD_FIRST_FTM_CHANNEL, kFTM_EdgeAlignedPwm,
                               100);
        FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)BOARD_SECOND_FTM_CHANNEL, kFTM_EdgeAlignedPwm,
                               100);
        /* Software trigger to update registers */
        FTM_SetSoftwareTrigger(BOARD_FTM_BASEADDR, true);


  //PRINTF("ScarabRobot project\n");
#if 1
 // GPIO_SetPinsOutput(BOARD_GLED_GPIO, 1U << BOARD_GLED_GPIO_PIN);
  //GPIO_SetPinsOutput(BOARD_RLED_GPIO, 1U << BOARD_RLED_GPIO_PIN);
  GPIO_ClearPinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);
  GPIO_SetPinsOutput(BOARD_GLED_GPIO, 1U << BOARD_GLED_GPIO_PIN);
  GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif






#if 1
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_A);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_B);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_A);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_B);
//  GPIO_ClearPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif



        i2c_init();


        //Flash Mem Init
        qflash_init();


          /* Enable Quad mode for the flash */
          enable_quad_mode();


         



          qspi_read(read_flashbuf1, 0x68000000, 1024);

      // write_ntag_data(write_buffer,16);
/*
          ntag_header[0]=0x00;
          ntag_header[1]=0x00;
          ntag_header[2]=0x00;
          write_ntag_header(ntag_header);
*/

      while(1){

          read_ntag_header(ntag_header);


          if(ntag_header[0]==0x01){


              GPIO_ClearPinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);
              GPIO_ClearPinsOutput(BOARD_GLED_GPIO, 1U << BOARD_GLED_GPIO_PIN);

              read_ntag_data(ntag_path,128);
#if 0
              xfer.data = ntag_path;
                              xfer.dataSize = sizeof(ntag_path);
                              txOnGoing = true;
                              LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                              /* Wait send finished */
                                 while (txOnGoing)
                                 {
                                 }
#endif
              run_scarab();


              ntag_header[0]=0x00;
              write_ntag_header(ntag_header);


          }

          if(ntag_header[2]==0x01){

              lights_on = true;
              GPIO_ClearPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);
          }else{

              lights_on =false;
              GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

          }




          switch(ntag_header[1]){


          case 0x00:
/*
                 xfer.data = string_scarab_idle;
                 xfer.dataSize = sizeof(string_scarab_idle);
                 txOnGoing = true;
                 LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                  Wait send finished
                    while (txOnGoing)
                    {
                    }
*/
                      GPIO_ClearPinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);
                      GPIO_SetPinsOutput(BOARD_GLED_GPIO, 1U << BOARD_GLED_GPIO_PIN);



                      for(i=0;i<128;i++){

                          ntag_path[i]=0x00;


                      }

              break;

          case 0x01:

/*
         xfer.data = string_scarab_active;
         xfer.dataSize = sizeof(string_scarab_active);
         txOnGoing = true;
         LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

          Wait send finished
            while (txOnGoing)
            {
            }
*/
              GPIO_SetPinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);
              GPIO_ClearPinsOutput(BOARD_GLED_GPIO, 1U << BOARD_GLED_GPIO_PIN);
              break;

          case 0x02:

              transfer_image();


              ntag_header[1]=0x00;
              write_ntag_header(ntag_header);


              break;


          }



#if 0


                    /* Get new accelerometer data. */
                                FXOS_ReadSensorData(&fxosHandle, &sensorData);

                                /* Get the X and Y data from the sensor data structure.fxos_data */
                                xData = (int16_t)((uint16_t)((uint16_t)sensorData.accelXMSB << 8) | (uint16_t)sensorData.accelXLSB);
                                yData = (int16_t)((uint16_t)((uint16_t)sensorData.accelYMSB << 8) | (uint16_t)sensorData.accelYLSB);

                                /* Convert raw data to angle (normalize to 0-90 degrees). No negative angles. */
                                xAngle = (int16_t)floor((double)xData * 0.011);
                                if (xAngle < 0)
                                {
                                    xAngle *= -1;
                                }
                                yAngle = (int16_t)floor((double)yData * 0.011);
                                if (yAngle < 0)
                                {
                                    yAngle *= -1;
                                }


                            if( (xAngle - pxAngle) > 3   || (pxAngle - xAngle) > 3){

                               IsMoving = true;

                            }
                            else{

                                IsMoving = false;
                            }

#endif

                            DelayMs(250);

                            DelayMs(250);

                            DelayMs(250);
                            DelayMs(250);
             }

  for(;;) { /* Infinite loop to avoid leaving the main function */
    __asm("NOP"); /* something to use as a breakpoint stop while looping */
  }
}




void run_scarab(){


int i;
int task_time = 10;
int step_time = 100;


delay_ms(10);

for(i=0;i<128;i++){





    switch(ntag_path[i]){

    case 0x00:
#if 0
         xfer.data = "stop\n";
                         xfer.dataSize = sizeof("stop\n");
                         txOnGoing = true;
                         LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                         /* Wait send finished */
                            while (txOnGoing)
                            {
                            }
#endif

            if(!lights_on)
            GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);
            step_time =100;
            turn_plus =0;
            stop();
            i=128;
        break;
    case 0x01:
#if 0
         xfer.data = "fwd\n";
                         xfer.dataSize = sizeof("fwd\n");
                         txOnGoing = true;
                         LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                         /* Wait send finished */
                            while (txOnGoing)
                            {
                            }
#endif
        step_time =100;
        turn_plus =0;
        if(!lights_on)
        GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

        move_forward();

        break;
    case 0x03:
#if 0
         xfer.data = "right\n";
                         xfer.dataSize = sizeof("right\n");
                         txOnGoing = true;
                         LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                         /* Wait send finished */
                            while (txOnGoing)
                            {
                            }
#endif
        step_time =60;
        turn_plus =40;
        if(!lights_on)
        GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

        move_left();
        break;


    case 0x04:
#if 0
         xfer.data = "left\n";
                         xfer.dataSize = sizeof("left\n");
                         txOnGoing = true;
                         LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                         /* Wait send finished */
                            while (txOnGoing)
                            {
                            }
#endif
        step_time =60;
        turn_plus =40;
        if(!lights_on)
        GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

        move_right();

        break;

    case 0x11:

        stop();

          GPIO_ClearPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

             BOARD_I2C_ReleaseBus();

             BOARD_I2C_ReConfig();

             FLEXIO_Ov7670Init();

             FLEXIO_Ov7670StartCapture(1);

             DelayMs(255);
             DelayMs(255);

             BOARD_I2C_ReleaseBus();

             BOARD_I2C_ReConfig();

             i2c_reset();
            copytoflash(0,g_FlexioCameraFrameBuffer);

        break;






    }

    delay_ms(task_time);


}



}


void transfer_image(){

    uint32_t i,j;


     for(i=0;i<38400;i++){

#if 1
        if(g_FlexioCameraFrameBuffer[i]==0x0D)
            g_FlexioCameraFrameBuffer[i] = 0x0E;
        else
            continue;

#endif
    //    g_FlexioCameraFrameBuffer[i]=05;

     }



     for(i=0;i<12;i++){

            xfer.data = &g_FlexioCameraFrameBuffer[i*3200];
            xfer.dataSize = 3200;
            txOnGoing = true;
            LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);


            /* Wait send finished */
            while (txOnGoing)
            {
            }

              GPIO_TogglePinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);
         DelayMs(100);

     }

        xfer.data = string_LF;
                    xfer.dataSize = 2;
                    txOnGoing = true;
                    LPUART_TransferSendNonBlocking(DEMO_LPUART, &g_lpuartHandle, &xfer);

                    /* Wait send finished */
                    while (txOnGoing)
                    {
                    }

                      GPIO_ClearPinsOutput(BOARD_BLED_GPIO, 1U << BOARD_BLED_GPIO_PIN);


}


void move_left(){




#if 1
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_A);


    /* Start PWM mode with updated duty cycle */
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR1_B, kFTM_EdgeAlignedPwm,
                           3);
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR2_A, kFTM_EdgeAlignedPwm,
                           100);
    /* Software trigger to update registers */
    FTM_SetSoftwareTrigger(BOARD_FTM_BASEADDR, true);


  //GPIO_SetPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_B);
  //GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_A);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_B);
//  GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif


}


void move_right(){

    int i;



#if 1
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_A);


    /* Start PWM mode with updated duty cycle */
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR1_B, kFTM_EdgeAlignedPwm,
                           100);
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR2_A, kFTM_EdgeAlignedPwm,
                           0);
    /* Software trigger to update registers */
    FTM_SetSoftwareTrigger(BOARD_FTM_BASEADDR, true);

  //GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_B);
  //GPIO_SetPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_A);



  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_B);
//  GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif


}

void move_forward(){




#if 1
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_A);


    /* Start PWM mode with updated duty cycle */
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR1_B, kFTM_EdgeAlignedPwm,
                           9);
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR2_A, kFTM_EdgeAlignedPwm,
                           0);
    /* Software trigger to update registers */
    FTM_SetSoftwareTrigger(BOARD_FTM_BASEADDR, true);


  //GPIO_SetPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_B);
  //GPIO_SetPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_A);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_B);
//  GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif


}

void stop(){

int i;


#if 1
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_A);
  GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_B);

  for(i=12;i<=100;i=i+2){

    /* Start PWM mode with updated duty cycle */
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR1_B, kFTM_EdgeAlignedPwm,
                           100);
    FTM_UpdatePwmDutycycle(BOARD_FTM_BASEADDR, (ftm_chnl_t)MOTOR2_A, kFTM_EdgeAlignedPwm,
                           100);
    /* Software trigger to update registers */
    FTM_SetSoftwareTrigger(BOARD_FTM_BASEADDR, true);

    DelayMs(200);

  }


 // GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR1_B);
  //GPIO_ClearPinsOutput(BOARD_MOTOR_GPIO, 1U << MOTOR2_A);

//  GPIO_SetPinsOutput(BOARD_LIGHT_GPIO, 1U << LIGHT_LED);

#endif


}
void delay_ms(int dly){

    while(dly--){
    DelayMs(255);
    }

}

Credits

Ashok R

Ashok R

37 projects • 102 followers
Hobbyist/Engineer/Director/Animatior

Comments