4588 views|3 replies

2618

Posts

0

Resources
The OP
 

TI's vehicle controller solution design makes your design easier. [Copy link]

In electric vehicles, VCU is the core control component. TI provides the design scheme of the vehicle control unit (VCU) and the related schematic design reference. Friends who are engaged in the development of new energy vehicles can refer to it, which is very helpful for the development of new products. First, take a look at the overall block diagram of VCU as shown in Figure 1.
Figure 1
Figure 2
Figure 3
Figure 4
Figure 5
Figure 6
Figure 7
Figure 8
Figure 9
Figure 1、Figure 2、Figure 3、Figure 4、Figure 5、Figure 6、Figure 7 In Figures 8 and 9, the specific reference design schematics of the red-framed parts are shown in the attachment tidrs34b.pdf (1.24 MB, downloads: 30) , and the specific design contents in the attachment are shown in the following pictures. Have a feel for how it makes your design much simpler.
The TI MCU that can be used for the VCU here There are: TMS570LS3137, TMS570LS1224, TMS320F28375S, TMS320F28335, etc.
Figure 10
The part with a red frame in Figure 10 is the input protection design part. For the specific design schematic, see the attachment tidrop5.pdf (405.76 KB, downloads: 24) . Note that the design supports 12v and 24v power inputs. For the specific schematic, see Figure 11.
Figure 11


This post is from Microcontroller MCU

Latest reply

TI also develops vehicle controller solutions, it is indeed a big company  Details Published on 2018-10-11 08:35
 

102

Posts

0

Resources
2
 
I would also like to share a vehicle controller program written for TI's TMS320F28069 shared by netizens on github. I hope it will be helpful to everyone. Let’s take a look at the main program first //#################################################################// // Vehicle Control Unit V1 // // Created by Caner Alp // // 13.06.2018 // // // // The Project is for the electric vehicle car Mediterranean Shark // // by Team ADA // // Electric Vehicle Development Center // // Eastern Mediterranean University // //#################################################################// // // Libraries // #include "DSP28x_Project.h" #include
#include
#include "settingsGPIO.h"
#include "settingsCAN.h"
#include "settingsUART.h"
#include "mspControl.h"
#include "settingsPWM.h"
#include "math.h"
#include "settingsCla.h"
#include "IQmathLib.h"

//#define RAM
//#define _FLASH

//*****************************************************************************
// defines
//*****************************************************************************
#define maxSpeed    95         // Max Speed KM/H

// Steering Constant Definitions

#define aSteer      36.97165
#define bSteer      110.918
#define cSteer      50.65597
#define steerZero   176.992137
#define PI          3.1415926535


// Function Prototypes
//
void sendSpeed (Uint8 speed);
void processCanBusData(Uint8 command,Uint32 * data);

void calculateDifferential(float angle,Uint8 speed, Uint8 * innerSpeed, Uint8 * outerSpeed);
void reversePressed(void);
_iq calculateTireAngle (_iq angle);

__interrupt void cpu_timer0_isr(void);
__interrupt void ecan1intA_isr(void);
__interrupt void scibRxFifoIsr(void);
__interrupt void modeButton_isr (void);
//__interrupt void downButton_isr (void);
//******************************************************************************
// General State Machines ***************************************************
//******************************************************************************

typedef enum DRIVE_ModeEnum{
    AUTONOMOUS_MODE,
    NORMAL_MODE,
    TEST_MODE,
    CHARGE_MODE
} DRIVE_Mode;

/* Used to track the state of the software state machine*/
DRIVE_Mode driveMode = NORMAL_MODE;



typedef enum DIRECTION_ModeEnum{
    FORWARD,
    BACKWARD
} DIRECTON;

/* Used to track the state of the software state machine*/
DIRECTON directionMotors = FORWARD; // as default, the car will go in forward direction


typedef enum CHARGE_ModeEnum{
    chargeDISABLE,
    chargeENABLE
} CHARGE_Mode_Active;

CHARGE_Mode_Active chargeMode = chargeDISABLE;

typedef enum AUTONOMOUS_ModeEnum{
    autonomousDISABLE,
    autonomousENABLE
} AUTONOMOUS_Mode_Active;

AUTONOMOUS_Mode_Active autonomousStartEnable = autonomousDISABLE;

////*****************************************************************************
// globals
//*****************************************************************************
//
// Variable Prototypes For CAN-BUS
//
Uint32  canReceivedBuffer[8] = {0, 0, 0, 0, 0, 0, 0, 0};

Uint8 counter = 0;

Uint8 setSpeed          = 0;
Uint8 currentSpeed      = 0;
Uint8 minuteCounter     = 0;
Uint32 mainVoltage      = 0;
Uint32 maxTemperature   = 0;
float energyMeterFloat = 0.0;
float steeringAngle = 0.0;
float tempTemperature = 0.0;

Uint8 motorTempLeft = 0;
Uint8 motorTempRight = 0;
Uint8 motorSpeedLeft = 0;
Uint8 motorSpeedRight = 0;

Uint32 instantaneousPower = 0;
Uint32 mainCurrent = 0;
Uint32 chargeVoltage    = 0;
Uint32 chargeCurrent    = 0;
Uint32 brakePressed = 0;

Uint8 warningMessages   = 0;
Uint8 statusVehicle     = 0;

Uint8 chargeActive      = 0;
Uint8 motorLeftStatus   = 0;
Uint8 motorRigthStatus  = 0;
Uint8 bmsStatus         = 0;
Uint8 smpsStatus        = 0;

Uint8 ledData = 0;

Uint8 modeCounter = 0;

Uint8 ReceivedChar;

struct ECAN_REGS ECanaShadow;

float angleSteering = 0.0;

extern Uint16 RamfuncsLoadStart;
extern Uint16 RamfuncsLoadEnd;
extern Uint16 RamfuncsRunStart;
extern Uint16 RamfuncsLoadSize;
//
// main
//
void main(void)
{
    Uint8 levels = 0;
    //
    // Step 1. Initialize System Control:
    // PLL, WatchDog, enable Peripheral Clocks
    // external Xtal --> 90Mhz
    //
    InitSysCtrl();

    //
    // Disable Interrupts
    //
    DINT;
    //
    //
    //
    InitPieCtrl();
    //
    // Disable CPU interrupts and clear all CPU interrupt flags:
    //
    IER = 0x0000;
    IFR = 0x0000;
    //
    // Initialize the PIE vector table with pointers to the shell Interrupt
    // Service Routines (ISR).
    // This will populate the entire table, even if the interrupt
    // is not used in this example.  This is useful for debug purposes.
    // The shell ISR routines are found in f2802x_DefaultIsr.c.
    // This function is found in f2802x_PieVect.c.
    //
    InitPieVectTable();

    //
    // Interrupts that are used in this example are re-mapped to
    // ISR functions found within this file.
    EALLOW;
    PieVectTable.ECAN1INTA = &ecan1intA_isr;
    PieVectTable.TINT0 = &cpu_timer0_isr;
    /* * * * * * * * * * PWM * * * * * * * * * */
    // This is needed to write to EALLOW protected registers
    PieVectTable.EPWM1_INT = &epwm1_isr;
    PieVectTable.EPWM3_INT = &epwm3_isr;
    PieVectTable.EPWM4_INT = &epwm4_isr;
    /* * * * * * * * * *SCI* * * * * * * * * */
    //    PieVectTable.SCIRXINTA = &sciaRxFifoIsr;
    PieVectTable.SCIRXINTB = &scibRxFifoIsr;

    //PieVectTable.XINT1 = &modeButton_isr;
    //    PieVectTable.XINT2 = &downButton_isr;
    EDIS;

#ifdef _FLASH
    // Copy time critical code and Flash setup code to RAM
    // The  RamfuncsLoadStart, RamfuncsLoadSize, and RamfuncsRunStart
    // symbols are created by the linker. Refer to the F28069.cmd file.
    //
    memcpy(&RamfuncsRunStart, &RamfuncsLoadStart,
           (Uint32)&RamfuncsLoadSize);

    InitFlash();
#endif //FLASH

    InitCpuTimers();
    ConfigCpuTimer(&CpuTimer0, 90, 150000);

    pwmInit();//Initialize PWM Pins
    //
    // Initialize GPIO, and assign the output to deactiveted position
    //
    gpioInit();

    //
    // Initialize PWM, and set 0 not cause any power drain immedately
    //
    pwmInit();
    pwmWrite(0, HORN);        // duty cycle is 0
    pwmWrite(0, LIGHTS);      // duty cycle is 0
    pwmWrite(0, WIPER);       // duty cycle is 0

    //
    //Initialize SPI to communicate with MSP430
    //
    spiInit();

    //
    // Reset MSP to wake up and clear the device
    //
    resetMsp();

    //
    // Initialize CAN-BUS for Motor Control Boards, BMS and SMPS.
    //
    canBusInit();

//    gpioInterruptSetup();

    uartInit();

    //
    //  enable interrupts
    //
    //    sendSpeed(0);
    //
    // Enable TINT0 in the PIE: Group 1 interrupt 7
    //
    PieCtrlRegs.PIECTRL.bit.ENPIE = 1;   // Enable the PIE block
    PieCtrlRegs.PIEIER9.bit.INTx6 = 1;   // Enable ECAN1INTA in the PIE: Group 1 interrupt 7
    PieCtrlRegs.PIEIER1.bit.INTx7 = 1;   // Enable TINT0 in the PIE: Group 1 interrupt 6
    PieCtrlRegs.PIEIER1.bit.INTx4 = 1;   // Enable PIE Group 1 INT4, FOR XINT1 GPIO0, UP BUTTON
    //    PieCtrlRegs.PIEIER1.bit.INTx5 = 1;   // Enable PIE Group 1 INT5, FOR XINT2 GPIO15,DOWN BUTTON
    PieCtrlRegs.PIEIER9.bit.INTx3 = 1;      // Receive interrupt for SCI-B
    // for PWMS

    //   PieCtrlRegs.PIEIER2.bit.INTx1 = 1;
    //   PieCtrlRegs.PIEIER3.bit.INTx1 = 1; // Enable

    // M_INT9 For CAN-BUS
    // M_INT2 for PWM
    // M_INT1 for Timer0
    IER |= M_INT9 | M_INT2 | M_INT1;

    //
    //
    //
    // Enable global Interrupts and higher priority real-time debug events
    //
    EINT;               // Enable Global interrupt INTM
    ERTM;               // Enable Global realtime interrupt DBGM
    //
    // Initialize UART for LCD and RF transiciver
    //


//    delayms(1000000);
//    delayms(1000000);

    CpuTimer0Regs.TCR.all = 0x4000;

    while(1)
    {    // The modes will be controlled by the switch
        switch(driveMode)
        {
        case NORMAL_MODE:        // Normal Drive Control loop
            // When speed up button pressed
            if(!GpioDataRegs.GPADAT.bit.GPIO0 && GpioDataRegs.GPADAT.bit.GPIO15)
            {
                while(!GpioDataRegs.GPADAT.bit.GPIO0 );
                //   DELAY_US(5000);

                // increase the speed
                if(setSpeed < maxSpeed)   // if it reaches its maximum, assign maximum speed
                    setSpeed += 1;


                //                sendSpeed(setSpeed);
            }

            // When Speed down button pressed
            if(!GpioDataRegs.GPADAT.bit.GPIO15 && GpioDataRegs.GPADAT.bit.GPIO0)
            {
                while(!GpioDataRegs.GPADAT.bit.GPIO15);
                //       DELAY_US(5000);

                // decrease the speed
                if(setSpeed > 0)
                    setSpeed -= 1;

                // if it reaches its mininum, assign 0
                //                sendSpeed(setSpeed);
            }

            reversePressed();
            hornPressed();       // Check Horn Button
            lightsPressed();     // Check The ligths Switch
            controlFan(maxTemperature);        // Check the Temperature, if exceeds then turn FAN on.
            controlFlash(maxTemperature);      // In case fault, activate FLASH
            //
            // There is no wiper input specifically
            // the extra input is used, GPIO19
            //
            wiperPressed();
            //
            // There is no output for br ake,
            // The brake ligth must be connectted manually, directly to the switch
            // When foot brake is pressed the motors will do the action
            // based on the situtation
            //
            brakeSwitchPressed();
            tempTemperature = _IQtoF(maxTemperature);
/*            if(tempTemperature > maxTemperatureThreshold)
            {
                driveMode = TEST_MODE;
                setSpeed = 0;
            }
            */

            break;
        case AUTONOMOUS_MODE:     // Autonomus Drive Control Loop


            break;
        case TEST_MODE:          // Test Mode Loop, Will test the all components - Alarm Mode



            while(CpuTimer0.InterruptCount > 1)
            {
                if(levels == 0)
                {
                    pwmWrite(levels, LIGHTS);
                    pwmWrite(levels, HORN);
                    levels = 100;
                }

                else
                {
                    pwmWrite(levels, LIGHTS);
                    pwmWrite(levels, HORN);
                    levels = 0;
                }

                GpioDataRegs.GPATOGGLE.bit.GPIO9 = 1; // FLASHER ON
                GpioDataRegs.GPBTOGGLE.bit.GPIO32 = 1; // Brake Lights Blink

                CpuTimer0.InterruptCount = 0;
            }

            break;
        case CHARGE_MODE:


            break;
        }

        }

}
__interrupt void modeButton_isr (void)
{
    while(!GpioDataRegs.GPADAT.bit.GPIO1);

    if(currentSpeed == 0)
    {
        modeCounter++;
        if(modeCounter > 2) modeCounter = 0;

        switch(modeCounter)
        {
        case 0:
            ledData |= ledACTIVE;
            ledData &= ~ledAutoMode;
            driveMode = NORMAL_MODE;
            break;
        case 1:
            ledData &= ~ledACTIVE;
            ledData |= ledAutoMode;
            driveMode = AUTONOMOUS_MODE;
            break;
        case 2:
            ledData &= (~ledACTIVE) | (~ledAutoMode) ;
            driveMode = TEST_MODE;
            break;
        case 3:
            ledData &= (~ledACTIVE) | (~ledAutoMode);
            driveMode = CHARGE_MODE;
            break;
        }

        if(driveMode != AUTONOMOUS_MODE)
        {
            autonomousStartEnable = autonomousDISABLE;
        }


    }

    //
    // Acknowledge this interrupt to get more from group 1
    //
    PieCtrlRegs.PIEACK.all |= PIEACK_GROUP1;
}

/*__interrupt void downButton_isr (void)
{
    // Acknowledge this interrupt to get more from group 1
    //
    PieCtrlRegs.PIEACK.all = PIEACK_GROUP1;
} */


__interrupt void cpu_timer0_isr(void)       // Each Cycle is 200ms
{


    sendSpeed(setSpeed);
    CpuTimer0.InterruptCount++;
    //    if(CpuTimer0.InterruptCount == 99) CpuTimer0.InterruptCount = 0;

    asm (" NOP");asm (" NOP");asm (" NOP");asm (" NOP");asm (" NOP");asm (" NOP");asm (" NOP");
    uartSendtoLCD(currentSpeed, setSpeed, mainVoltage, maxTemperature);   // Update the screen each 200ms
    asm (" NOP");asm (" NOP");asm (" NOP");
    uartSendtoRF1(mainVoltage, mainCurrent, currentSpeed, maxTemperature, motorTempLeft);
    asm (" NOP");asm (" NOP");asm (" NOP");
    uartSendtoRF2(motorTempRight, motorSpeedLeft, motorSpeedRight, steeringAngle);

    if(maxTemperature > maxTemperatureThreshold)
        ledData |= ledFAULT1;
    else
        ledData  &= ~ledFAULT1;

    getFromBMS();
    //    mspSpi(CMD_LEDS_M, 1, &ledData);
    //    CpuTimer0.InterruptCount++;
    PieCtrlRegs.PIEACK.all |= PIEACK_GROUP1;
}

__interrupt void ecan1intA_isr(void)
{

    asm (" NOP");
    //    canInterruptCount++;
    unsigned int mailbox_nr;

    mailbox_nr = ECanaRegs.CANGIF1.bit.MIV1;
    switch(mailbox_nr)
    {
    case ID_MOTOR://Motor
        canReceivedBuffer[0] = ECanaMboxes.MBOX16.MDL.all;
        canReceivedBuffer[1] = ECanaMboxes.MBOX16.MDH.all;
        processCanBusData(ID_MOTOR, canReceivedBuffer);
        ECanaRegs.CANRMP.bit.RMP16 = 1;
        break;
    case ID_BMS_1://BMS
    case ID_BMS_2:
    case 22:
        canReceivedBuffer[0] = ECanaMboxes.MBOX18.MDL.all;
        canReceivedBuffer[1] = ECanaMboxes.MBOX18.MDH.all;

        canReceivedBuffer[2] = ECanaMboxes.MBOX19.MDL.all;
        canReceivedBuffer[3] = ECanaMboxes.MBOX19.MDH.all;

        canReceivedBuffer[4] = ECanaMboxes.MBOX22.MDL.all;
        canReceivedBuffer[5] = ECanaMboxes.MBOX22.MDH.all;

        ECanaRegs.CANRMP.bit.RMP18 = 1;
        ECanaRegs.CANRMP.bit.RMP19 = 1;
        ECanaRegs.CANRMP.bit.RMP22 = 1;
        processCanBusData(ID_BMS ,canReceivedBuffer);
        break;
    case ID_SMPS_1://SMPS
    case ID_SMPS_2://SMPS
        canReceivedBuffer[0] = ECanaMboxes.MBOX20.MDL.all;
        canReceivedBuffer[1] = ECanaMboxes.MBOX20.MDH.all;
        canReceivedBuffer[2] = ECanaMboxes.MBOX21.MDL.all;
        canReceivedBuffer[3] = ECanaMboxes.MBOX21.MDH.all;

        processCanBusData(ID_SMPS ,canReceivedBuffer);
        ECanaRegs.CANRMP.bit.RMP20 = 1;
        ECanaRegs.CANRMP.bit.RMP21 = 1;
        break;

    }
    PieCtrlRegs.PIEACK.bit.ACK9|= 1;       // Issue PIE ack
}


__interrupt void scibRxFifoIsr(void)
{
    ReceivedChar = ScibRegs.SCIRXBUF.all;

    if(ReceivedChar == 1 && driveMode == AUTONOMOUS_MODE)
    {
        autonomousStartEnable = autonomousENABLE;

    }
    else
        autonomousStartEnable = autonomousDISABLE;

    ScibRegs.SCIFFRX.bit.RXFFOVRCLR=1;   // Clear Overflow flag
    ScibRegs.SCIFFRX.bit.RXFFINTCLR=1;   // Clear Interrupt flag

    PieCtrlRegs.PIEACK.all|=0x100;       // Issue PIE ack
}


void reversePressed(void)
{
    if(setSpeed == 0)
    {
        if(!GpioDataRegs.GPADAT.bit.GPIO13)

            directionMotors = BACKWARD;

        else
            directionMotors = FORWARD;
    }
}

void sendSpeed (Uint8 speed)
{
    Uint32 direction;
    Uint32 canH = 0;
    Uint32 canL = 0;

    Uint8 leftSpeed = speed;
    Uint8 rightSpeed = speed;
    Uint32 brakeTemp = 0;

    Uint8 innerSpeed = 0;
    Uint8 outerSpeed = 0;
    float angle = 0;

    _iq angleIQ;

    //    if(GpioDataRegs.GPADAT.bit.GPIO11) directionMotors = FORWARD;
    //    else directionMotors = BACKWARD;

    if(directionMotors == FORWARD)
        direction = DIRECTION;
    else
        direction = 0;

    // Get the Steering Angle
        steeringAngle = getSteeringAngle();
        angle = steeringAngle;

   if(!GpioDataRegs.GPADAT.bit.GPIO1)
   {
    // Calculate the outer side angle
    // Calculate the angle of the outer tire so Left tire angle will be calculated
    if(angle < (steerZero - 5.0))       // Steering is turned to RIGHT
    {                           // SPEED for LEFT
        angle = steerZero - steeringAngle;
        angleIQ = _IQ(angle);
        angleIQ = calculateTireAngle(angleIQ);
        angle = _IQtoF(angleIQ);
        calculateDifferential(angle, speed, &innerSpeed, &outerSpeed);
        leftSpeed = outerSpeed;
        rightSpeed = innerSpeed;

    }
    else if (angle > (steerZero + 5.0))                   // Steering is turned to LEFT
    {                       // Right tire will be OUTER
                            // Speed for RIGHT
        angle = steeringAngle - steerZero;
        angleIQ = _IQ(angle);
        angleIQ = calculateTireAngle(angleIQ);

        angle = _IQtoF(angleIQ);
        calculateDifferential(angle, speed, &innerSpeed, &outerSpeed);
        rightSpeed = outerSpeed;
        leftSpeed = innerSpeed;

    }
    else
    {
        leftSpeed = speed;
        rightSpeed = speed;
    }
   }
   else
   {
       leftSpeed = speed;
       rightSpeed = speed;
   }

    if(brakePressed)
    {
        brakeTemp = BRAKE;
    }
    else
        brakeTemp = 0;

    canL = direction | brakeTemp |(rightSpeed << 8) | leftSpeed;

    canBusTransmit(&canL, &canH, ID_MOTOR);
}


void processCanBusData(Uint8 command,Uint32 * data)
{

    switch(command)
    {
    case ID_MOTOR:

        currentSpeed = data[0] & 0x000000FF;
        motorTempLeft = data[1] & 0x000000FF;
        motorTempRight = (Uint8) (data[1] & 0x0000FF00) >> 8;
        motorSpeedLeft = (Uint8) ((data[1] & 0x00FF0000) >> 16);
        motorSpeedRight = (Uint8) ((data[1] & 0xFF000000) >> 24);

        if(brakePressed)
            setSpeed = currentSpeed;

        break;

    case ID_BMS:

        mainVoltage = data[0];
        maxTemperature = data[1];
        energyMeterFloat = data[2];
        instantaneousPower = data[3];
        mainCurrent = data[4];
        bmsStatus = data[5];

        break;
    case ID_SMPS:

        chargeVoltage = data[0] & 0x0000FFFF;
        chargeCurrent = (data[0] & 0xFFFF0000) >> 16;
        smpsStatus = data[1] & 0xFF000000;
        break;
    }
}


void calculateDifferential(float angle,Uint8 speed, Uint8 * innerSpeed, Uint8 * outerSpeed)
{
    float RL;
    float W;        // Omega
    float tan;

    //    angleInput = angle;
    angle = (angle * PI) / 180.0;

    tan = tanf(angle);

    RL = (-542 + (1850 / tan));

    W = ((float) speed)/RL;

    innerSpeed[0] = (Uint8)(W * (RL - 470.5));      // InnerSpeed
    outerSpeed[0] = (Uint8)(W * (RL + 470.5));      // OuterSpeed
}

_iq calculateTireAngle (_iq angle)
{
    _iq tempX;
    _iq10 tempZ;
    _iq tempW;
    _iq tempY;

    tempX = angle - _IQ(bSteer);
    tempX = _IQmpy(tempX,tempX);

    tempZ = _IQdiv(tempX, _IQ(-6419.797873));

    tempW = _IQexp(tempZ);

    tempY = _IQmpy(_IQ(aSteer), tempW);

    return tempY;
}


是不是还不错,最后看看一下完整的程序,详见附件 VCU_TMS_V1-master.zip (656.22 KB, downloads: 21)
This post is from Microcontroller MCU
 
 

2w

Posts

341

Resources
3
 
TI also develops vehicle controller solutions, it is indeed a big company
This post is from Microcontroller MCU

Comments

Yes, Freescale’s chips were used to make complete vehicle solutions, but now TI has also done it. TI provides a lot of reference design information, making development easy.  Details Published on 2018-10-11 09:25
 
 
 

2618

Posts

0

Resources
4
 
qwqwqw2088 Published on 2018-10-11 08:35 TI is also engaged in vehicle controller solutions. It is indeed a big company
Yes, Freescale’s chips were used to make vehicle solutions. Now TI is also doing it. TI provides a lot of reference design materials, which makes development easy.
This post is from Microcontroller MCU
 
 
 

Guess Your Favourite
Find a datasheet?

EEWorld Datasheet Technical Support

Copyright © 2005-2024 EEWORLD.com.cn, Inc. All rights reserved 京B2-20211791 京ICP备10001474号-1 电信业务审批[2006]字第258号函 京公网安备 11010802033920号
快速回复 返回顶部 Return list