Programme d'utilisation servomotors MX12 V1
Revision 0:80df663dd15e, committed 2017-05-19
- Comitter:
- R66Y
- Date:
- Fri May 19 14:32:14 2017 +0000
- Commit message:
- programme pour utiliser les servomoteurs MX12.
Changed in this revision
diff -r 000000000000 -r 80df663dd15e AX12/AX12.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/AX12/AX12.cpp Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,1577 @@ +/* mbed AX-12+ Servo Library + * + * Copyright (c) 2010, cstyles (http://mbed.org) + * + * 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. + */ + +#include "mbed.h" +#include "AX12.h" + +#define MAX_TIMEOUT 500 + +extern Timer t; + +typedef struct +{ + unsigned short Model_Number; + unsigned char Firmware; + unsigned char ID; + unsigned char Baud_Rate; + unsigned char Return_Delay_Time; + unsigned short CW_Angle_Limit; + unsigned short CCW_Angle_Limit; + unsigned char Reserved1; + unsigned char Highest_Limit_Temperature; + unsigned char Lowest_Limit_voltage; + unsigned char Highest_Limit_voltage; + unsigned short Max_Torque; + unsigned char Status_Return_Level; + unsigned char Alarm_LED; + unsigned char Alarm_Shutdown; + unsigned char Reserved2; + unsigned short Down_Calibration; + unsigned short Up_Calibration; + unsigned char Torque_Enable; + unsigned char LED; + unsigned char CW_Compliance_Margin; + unsigned char CCW_Compliance_Margin; + unsigned char CW_Compliance_Slope; + unsigned char CCW_Compliance_Slope; + unsigned short Goal_Position; + unsigned short Moving_Speed; + unsigned short Torque_Limit; + unsigned short Present_Position; + unsigned short Present_Speed; + unsigned short Present_Load; + unsigned char Present_Voltage; + unsigned char Present_Temperature; + unsigned char Registered_Instruction; + unsigned char Reserved3; + unsigned char Moving; + unsigned char Lock; + unsigned short Punch; +} T_AX12; + + +AX12::AX12(PinName tx, PinName rx, int ID, int baud) + : _ax12(tx,rx) +{ + _baud = baud; + _ID = ID; + _ax12.baud(_baud); + + +} + +int AX12::Set_Secure_Goal(int degres) +{ + int error = 0; + int position = 0; + int difference = 0; + int timeout_secure = 0; + int autorisation = 0; + + position = Get_Position(); + error = Set_Goal(degres); + + while ((autorisation == 0) && (timeout_secure < 100) ) + { + position = Get_Position(); + //printf("position : %d", position ); + error = Set_Goal(degres); + //printf("degres : %d", degres); + difference = degres - position; + //printf ("difference : %d", difference ); + if (((difference < 2) && (difference > (-2) ))) + autorisation = 1; + + timeout_secure++; + } + + if ( timeout_secure == 100) + { + #ifdef AX12_DEBUG + printf (" timeout secure error "); + #endif + return(-1); + } + return(error); +} + + +int AX12::Get_Return_Delay_Time(void) +{ + char data[1]; + int ErrorCode = read(_ID, AX12_REG_DELAY_TIME, 1, data); + int time = data[0]; + time = 2.0 * time; + return(time); +} + + +int AX12::Get_Baud_Rate(void) +{ + char data[1]; + int ErrorCode = read(_ID, AX12_REG_BAUD, 1, data); + int baud = data[0]; + baud = 2000000 / ( baud + 1 ); + return(baud); +} + + +/** Reglage du courant minimum necessaire au bon fonctionnement de l'actionneur +// minimum >> Ox000 >> decimal 0 +// maximum >> 0x3FF >> decimal 1023 +// deflaut >> 0x20 >> decimal 32 +*/ +int AX12::Set_Punch(int punch) +{ + char data[2]; + + data[0] = punch & 0xff; // bottom 8 bits + data[1] = punch >> 8; // top 8 bits + + // write the packet, return the error code + return (write(_ID, AX12_REG_PUNCH, 2, data)); + +} + +/** Reset +*/ +int AX12::Reset(int punch) +{ + char data[2]; + + data[0] = punch & 0xff; // bottom 8 bits + data[1] = punch >> 8; // top 8 bits + + // write the packet, return the error code + return (write(_ID, 0x06, 1,data)); + +} + +int AX12::Get_Punch (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_PUNCH, 2, data); + int punch = data[0] | (data[1]<<8); + return(punch); +} + + +int AX12::Get_Load_Direction (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_PRESENT_LOAD, 2, data); + int direction = (data[1]>>2) & 0x01; + return(direction); +} + + +int AX12::Get_Load_Value (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_PRESENT_LOAD, 2, data); + int Load = (data[0] | (data[1]<<8)) & 0x3FF; + return(Load); +} + + +int AX12::Get_Present_Speed (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_PRESENT_SPEED, 2, data); + int speed = data[0] | (data[1]<<8); + return(speed); +} + + +int AX12::Get_CCW_Angle_Limit (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_CCW_LIMIT, 2, data); + int angle = data[0] | (data[1]<<8); + angle = (angle * 300) / 1023; + return(angle); +} + + +int AX12::Get_CW_Angle_Limit (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_CW_LIMIT, 2, data); + int angle = data[0] | (data[1]<<8); + angle = (angle * 300) / 1023; + return(angle); +} + + + +int AX12::Get_Torque_Enable(void) +{ + char data[1]; + int ErrorCode = read(_ID, AX12_REG_TORQUE_ENABLE, 1, data); + int enable = data[0]; + return(enable); +} + + +int AX12::Set_Torque_Enable(int etat) +{ + char data[1]; + data [0] = etat; + + int error = write(_ID, AX12_REG_TORQUE_ENABLE, 1, data); + return (error); +} + + + +int AX12::Get_Up_Calibration (void) +{ + char data[1]; + int ErrorCode = read(_ID, AX12_REG_UP_CALIBRATION, 2, data); + int Up_calibration = data[0] | (data[1]<<8); + return(Up_calibration); +} + + + +int AX12::Get_Down_Calibration (void) +{ + char data[1]; + int ErrorCode = read(_ID, AX12_REG_DOWN_CALIBRATION, 2, data); + int Dowm_calibration = data[0] | (data[1]<<8); + return(Dowm_calibration); +} + + + +int AX12::Get_ID(void) +{ + + char data[1]={-1}; + int ErrorCode = read(_ID, AX12_REG_ID, 1, data); + int id = data[0]; + return(id); +} + + +// Lecture du couple maximum ( retourne la valeur du registre Max Torque de l'AX12 ) +int AX12::Get_Max_Torque (void) +{ + char data[2]; + int ErrorCode = read(_ID, AX12_REG_MAX_TORQUE, 2, data); + int torque = data[0] | (data[1]<<8); + return(torque); +} + + + +/** Reglage du couple maximum de l'actionneur +// minimum >> Ox000 >> decimal 0 +// maximum >> 0x3FF >> decimal 1023 +// deflaut >> >> decimal +*/ +int AX12::Set_Max_Torque(int torque) +{ + char data[2]; + + data[0] = torque & 0xff; // bottom 8 bits + data[1] = torque >> 8; // top 8 bits + + // write the packet, return the error code + return (write(_ID, AX12_REG_MAX_TORQUE, 2, data)); + +} + + + + +/** Reglage de la desactivation des actionneurs si une erreur le concernant se produit +Bit Function +Bit 7 0 +Bit 6 If set to 1, torque off when an Instruction Error occurs +Bit 5 If set to 1, torque off when an Overload Error occurs +Bit 4 If set to 1, torque off when a Checksum Error occurs +Bit 3 If set to 1, torque off when a Range Error occurs +Bit 2 If set to 1, torque off when an Overheating Error occurs +Bit 1 If set to 1, torque off when an Angle Limit Error occurs +Bit 0 If set to 1, torque off when an Input Voltage Error occurs +*/ +int AX12::Set_Alarm_Shutdown(int valeur) +{ + char data[1]; + data [0] = valeur; + + int val_alarm_shutdown = write(_ID, AX12_REG_ALARM_SHUTDOWN, 1, data); + return (val_alarm_shutdown); +} + + + +/** Reglage de l'activation de l'alarme +Bit Function +Bit 7 0 +Bit 6 If set to 1, the LED blinks when an Instruction Error occurs +Bit 5 If set to 1, the LED blinks when an Overload Error occurs +Bit 4 If set to 1, the LED blinks when a Checksum Error occurs +Bit 3 If set to 1, the LED blinks when a Range Error occurs +Bit 2 If set to 1, the LED blinks when an Overheating Error occurs +Bit 1 If set to 1, the LED blinks when an Angle Limit Error occurs +Bit 0 If set to 1, the LED blinks when an Input Voltage Error occurs +*/ +int AX12::Set_Alarm_LED(int valeur) +{ + char data[1]; + data [0] = valeur; + + int val_alarmLED = write(_ID, AX12_REG_ALARM_LED, 1, data); + return (val_alarmLED); +} + + + + +// Reglage de la réponse à une instruction +// 0 >> ne repond a aucune instructions +// 1 >> repond seulement aux instructions READ_DATA +// 2 >> repond à toutes les instructions +int AX12::Set_Status_Return_Level(int etat) +{ + char data[1]; + data [0] = etat; + + int val_return_lvl = write(_ID, AX12_REG_SATUS_RETURN, 1, data); + return (val_return_lvl); +} + + +// Reglage de la tension minimale +// minimum >> Ox32 >> decimal 50 +// maximum >> 0xFA >> decimal 250 +// deflaut >> 0x3C >> decimal 60 +int AX12::Set_Lowest_Voltage(int val_lowest_voltage) +{ + char data[1]; + data [0] = val_lowest_voltage; + + int val_lowvolt = write(_ID, AX12_REG_LOWEST_VOLTAGE, 1, data); + return (val_lowvolt); +} + + +// Reglage de la tension maximale +// minimum >> Ox32 >> decimal 50 +// maximum >> 0xFA >> decimal 250 +// deflaut >> 0xBE >> decimal 190 +int AX12::Set_Highest_Voltage(int val_highest_voltage) +{ + char data[1]; + data [0] = val_highest_voltage; + + int val_highvolt = write(_ID, AX12_REG_HIGHEST_VOLTAGE, 1, data); + return (val_highvolt); +} + + +// Reglage du return time delay EN MICRO SECONDE 2uSec * val_delay_time +// minimum >> 0 us +// maximum >> 508 us +// deflaut >> 125 us +int AX12::Set_Delay_Time (int val_delay_time ) + { + char data[1]; + data [0] = val_delay_time/2.0; + + int valdelay_time = write(_ID, AX12_REG_DELAY_TIME, 1, data); + return (valdelay_time ); + } + + +// Reglage de la température max du cervo +// minimum >> Ox00 >> decimal 0 +// maximum >> 0x96 >> decimal 150 +int AX12::Set_Temperature_Max (int val_temperature ) + { + char data[1]; + data [0] = val_temperature; + + int valtemp_max = write(_ID, AX12_REG_TEMP_MAX, 1, data); + return (valtemp_max ); + } + +// Etat LED +// 0 = off +// 1 = on +int AX12::Set_Etat_LED(int etat) +{ + char data[1]; + data [0] = etat; + + int valLED = write(_ID, AX12_REG_LED, 1, data); + return (valLED); +} + +// Set the mode of the servo +// 0 = Positional (0-300 degrees) +// 1 = Rotational -1 to 1 speed +int AX12::Set_Mode(int mode) +{ + + if (mode == 1) { // set CR + //wait(0.001); + Set_CW_Angle_Limit(0); + //wait(0.001); + Set_CCW_Angle_Limit(0); + //wait(0.001); + Set_CR_Speed(0.0); + //wait(0.001); + } else { + //wait(0.001); + Set_CW_Angle_Limit(0); + //wait(0.001); + Set_CCW_Angle_Limit(300); + //wait(0.001); + Set_CR_Speed(0.0); + //wait(0.001); + } + return(0); +} + +int AX12::Set_Goal_speed(int speed, int flags) +{ + + char reg_flag = 0; + char data[2]; + + // set the flag is only the register bit is set in the flag + if (flags == 0x2) { + reg_flag = 1; + } + + data[0] = speed & 0xff; // bottom 8 bits + data[1] = speed >> 8; // top 8 bits + + // write the packet, return the error code + int rVal = write(_ID, AX12_REG_MOVING_SPEED, 2, data, reg_flag); + + /*if (flags == 1) { + // block until it comes to a halt + while (isMoving()) + { + } + + }*/ + return(rVal); +} + + +// if flag[0] is set, were blocking +// if flag[1] is set, we're registering +// they are mutually exclusive operations +int AX12::Set_Goal(int degrees, int flags) +{ + + char reg_flag = 0; + char data[2]; + + // set the flag is only the register bit is set in the flag + if (flags == 0x2) { + reg_flag = 1; + } + + // 1023 / 300 * degrees + short goal = (1023 * degrees) / 300; +#ifdef AX12_DEBUG + printf("SetGoal to 0x%x\n",goal); +#endif + + data[0] = goal & 0xff; // bottom 8 bits + data[1] = goal >> 8; // top 8 bits + + // write the packet, return the error code + int rVal = write(_ID, AX12_REG_GOAL_POSITION, 2, data, reg_flag); + + /*if (flags == 1) { + // block until it comes to a halt + while (isMoving()) + { + } + + }*/ + return(rVal); +} + + +// Set continuous rotation speed from -1 to 1 +int AX12::Set_CR_Speed(float speed) +{ + + // bit 10 = direction, 0 = CCW, 1=CW + // bits 9-0 = Speed + char data[2]; + + int goal = (0x3ff * abs(speed)); + + // Set direction CW if we have a negative speed + if (speed < 0) { + goal |= (0x1 << 10); + } + + data[0] = goal & 0xff; // bottom 8 bits + data[1] = goal >> 8; // top 8 bits + + // write the packet, return the error code + int rVal = write(_ID, 0x20, 2, data); + + return(rVal); +} + + +int AX12::Set_CW_Angle_Limit (int degrees) +{ + + char data[2]; + + // 1023 / 300 * degrees + short limit = (1023 * degrees) / 300; + +#ifdef AX12_DEBUG + printf("SetCWLimit to 0x%x\n",limit); +#endif + + data[0] = limit & 0xff; // bottom 8 bits + data[1] = limit >> 8; // top 8 bits + + // write the packet, return the error code + return (write(_ID, AX12_REG_CW_LIMIT, 2, data)); + +} + +int AX12::Set_CCW_Angle_Limit (int degrees) +{ + + char data[2]; + + // 1023 / 300 * degrees + short limit = (1023 * degrees) / 300; + +#ifdef AX12_DEBUG + printf("SetCCWLimit to 0x%x\n",limit); +#endif + + data[0] = limit & 0xff; // bottom 8 bits + data[1] = limit >> 8; // top 8 bits + + // write the packet, return the error code + return (write(_ID, AX12_REG_CCW_LIMIT, 2, data)); +} + + +int AX12::Set_ID (int CurrentID, int NewID) +{ + + char data[1]; + data[0] = NewID; + +#ifdef AX12_DEBUG + printf("Setting ID from 0x%x to 0x%x\n",CurrentID,NewID); +#endif + + return (write(CurrentID, AX12_REG_ID, 1, data)); + +} + + +int AX12::Set_Baud (int baud) +{ + + char data[1]; + data[0] = baud; + +#ifdef AX12_DEBUG + printf("Setting Baud rate to %d\n",baud); +#endif + + return (write(_ID, AX12_REG_BAUD, 1, data)); + +} + + + +// return 1 is the servo is still in flight +int AX12::isMoving(void) +{ + + char data[1]; + read(_ID,AX12_REG_MOVING,1,data); + return(data[0]); +} + +void AX12::reset() +{ + + unsigned char TxBuf[16]; + unsigned char sum = 0; + unsigned long debut=0; + +#ifdef AX12_TRIGGER_DEBUG + // Build the TxPacket first in RAM, then we'll send in one go + printf("\nreset\n"); + printf("\nreset Packet\n Header : 0xFF, 0xFF\n"); +#endif + + TxBuf[0] = 0xFF; + TxBuf[1] = 0xFF; + + // ID - Broadcast + TxBuf[2] =_ID; + sum += TxBuf[2]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" ID : %d\n",TxBuf[2]); +#endif + + // Length + TxBuf[3] = 0x02; + sum += TxBuf[3]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Length %d\n",TxBuf[3]); +#endif + + // Instruction - ACTION + TxBuf[4] = 0x06; //reset + sum += TxBuf[4]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Instruction 0x%X\n",TxBuf[5]); +#endif + + // Checksum + TxBuf[5] = 0xFF - sum; +//#ifdef AX12_TRIGGER_DEBUG + printf(" Checksum 0x%X\n",TxBuf[5]); +//#endif + + // Transmit the packet in one burst with no pausing + for (int i = 0; i < 6 ; i++) + { + while(_ax12.writeable()==0); + _ax12.putc(TxBuf[i]); + + } + wait(0.001); + debut=t.read_ms(); + + do + { + if (_ax12.readable()==-1) // reception du premier Header ( 0xFF ) + printf("%02x",_ax12.getc()); + } + while((t.read_ms()-debut)<500); + + printf("\n"); + return; +} + +void AX12::read_all_info(unsigned char start, unsigned char longueur) +{ + + unsigned char TxBuf[16]; + unsigned char sum = 0; + unsigned long debut=0; + +#ifdef AX12_TRIGGER_DEBUG + // Build the TxPacket first in RAM, then we'll send in one go + printf("\nreset\n"); + printf("\nreset Packet\n Header : 0xFF, 0xFF\n"); +#endif + + TxBuf[0] = 0xFF; + TxBuf[1] = 0xFF; + + // ID - Broadcast + TxBuf[2] =_ID; + sum += TxBuf[2]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" ID : %d\n",TxBuf[2]); +#endif + + // Length + TxBuf[3] = 0x04; + sum += TxBuf[3]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Length %d\n",TxBuf[3]); +#endif + + // Instruction - ACTION + TxBuf[4] = INST_READ; //reset + sum += TxBuf[4]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Instruction 0x%X\n",TxBuf[4]); +#endif + + TxBuf[5] = start; //reset + sum += TxBuf[5]; + + TxBuf[6] = longueur; //reset + sum += TxBuf[6]; + + + // Checksum + TxBuf[7] = 0xFF - sum; +//#ifdef AX12_TRIGGER_DEBUG + //printf(" Checksum 0x%X\n\r",TxBuf[7]); +//#endif + + // Transmit the packet in one burst with no pausing + for (int i = 0; i < 8 ; i++) + { + while(_ax12.writeable()==0); + _ax12.putc(TxBuf[i]); + + } + + debut=t.read_ms(); + int i=0; + do + { + if (_ax12.readable()) + { // reception du premier Header ( 0xFF ) + printf("%02d:%02x ",start+i,_ax12.getc()); + i++; + } + } + while((t.read_ms()-debut)<5000); + + printf("\n"); + return; +} + + +void AX12::trigger(void) +{ + + char TxBuf[16]; + char sum = 0; + +#ifdef AX12_TRIGGER_DEBUG + // Build the TxPacket first in RAM, then we'll send in one go + printf("\nTriggered\n"); + printf("\nTrigger Packet\n Header : 0xFF, 0xFF\n"); +#endif + + TxBuf[0] = 0xFF; + TxBuf[1] = 0xFF; + + // ID - Broadcast + TxBuf[2] = 0xFE; + sum += TxBuf[2]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" ID : %d\n",TxBuf[2]); +#endif + + // Length + TxBuf[3] = 0x02; + sum += TxBuf[3]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Length %d\n",TxBuf[3]); +#endif + + // Instruction - ACTION + TxBuf[4] = 0x04; + sum += TxBuf[4]; + +#ifdef AX12_TRIGGER_DEBUG + printf(" Instruction 0x%X\n",TxBuf[5]); +#endif + + // Checksum + TxBuf[5] = 0xFF - sum; +#ifdef AX12_TRIGGER_DEBUG + printf(" Checksum 0x%X\n",TxBuf[5]); +#endif + + // Transmit the packet in one burst with no pausing + for (int i = 0; i < 6 ; i++) { + _ax12.putc(TxBuf[i]); + } + + // This is a broadcast packet, so there will be no reply + return; +} + + +float AX12::Get_Position(void) +{ + + #ifdef AX12_DEBUG + printf("\nGetPositionID(%d)",_ID); + #endif + + char data[2]; + + int ErrorCode = read(_ID, AX12_REG_POSITION, 2, data); + int position = data[0] | (data[1] << 8); + float angle = ((float)position * 300.0)/1023.0; + + return (angle); +} + + +float AX12::Get_Temp () +{ + +#ifdef AX12_DEBUG + printf("\nGetTemp(%d)",_ID); +#endif + + char data[1]; + int ErrorCode = read(_ID, AX12_REG_TEMP, 1, data); + float temp = data[0]; + return(temp); +} + + +float AX12::Get_Volts (void) +{ + +#ifdef AX12_DEBUG + printf("\nGetVolts(%d)",_ID); +#endif + + char data[1]; + int ErrorCode = read(_ID, AX12_REG_VOLTS, 1, data); + float volts = data[0]/10.0; + return(volts); +} + + +int AX12::read(int ID, int start, int bytes, char* data) { + + + char PacketLength = 0x3; + char TxBuf[16]; + char sum = 0; + char Status[16]; + + int timeout = 0; + int plen = 0; + int flag_out = 0; + int timeout_transmit = 0; + int i = 0; + int enable = 0; +// int poubelle = 0; +// int count = 0; +// char vidage[50]; + + typedef enum {Header1, Header2, ident, length, erreur, reception, checksum} type_etat; + type_etat etat = Header1; + + Status[4] = 0xFE; // return code + + + + + +/*********************************** CREATION DE LA TRAME A EVOYER *****************************************/ + +#ifdef AX12_READ_DEBUG + printf("\nread(%d,0x%x,%d,data)\n",ID,start,bytes); +#endif + + // Build the TxPacket first in RAM, then we'll send in one go +#ifdef AX12_READ_DEBUG + printf("\nInstruction Packet\n Header : 0xFF, 0xFF\n"); +#endif + + TxBuf[0] = 0xff; + TxBuf[1] = 0xff; + + // ID + TxBuf[2] = ID; + sum += TxBuf[2]; + +#ifdef AX12_READ_DEBUG + printf(" ID : %d\n",TxBuf[2]); +#endif + + // Packet Length + TxBuf[3] = 4;//PacketLength+bytes; // Length = 4 ; 2 + 1 (start) = 1 (bytes) + sum += TxBuf[3]; // Accululate the packet sum + +#ifdef AX12_READ_DEBUG + printf(" Length : 0x%x\n",TxBuf[3]); +#endif + + // Instruction - Read + TxBuf[4] = 0x2; + sum += TxBuf[4]; + +#ifdef AX12_READ_DEBUG + printf(" Instruction : 0x%x\n",TxBuf[4]); +#endif + + // Start Address + TxBuf[5] = start; + sum += TxBuf[5]; + +#ifdef AX12_READ_DEBUG + printf(" Start Address : 0x%x\n",TxBuf[5]); +#endif + + // Bytes to read + TxBuf[6] = bytes; + sum += TxBuf[6]; + +#ifdef AX12_READ_DEBUG + printf(" No bytes : 0x%x\n",TxBuf[6]); +#endif + + // Checksum + TxBuf[7] = 0xFF - sum; +#ifdef AX12_READ_DEBUG + printf(" Checksum : 0x%x\n",TxBuf[7]); +#endif +/********************************************TRAME CONSTRUITE DANS TxBuf***************************************/ + + + + + /* Transmission de la trame construite precedemment dans le tableau TxBuf + */ + while ((timeout_transmit<5000) && (i < (7+bytes))) + { + if (_ax12.writeable()) + { + _ax12.putc(TxBuf[i]); + i++; + timeout_transmit = 0; + } + else timeout_transmit++; + } + + if (timeout_transmit == 5000 ) // dans le cas d'une sortie en timeout pour ne pas rester bloquer ! + { + #ifdef AX12_DEBUG + printf ("timeout transmit erreur\r\n"); + #endif + return(-1); + } + /* Transmission effectuée on va ensuite récuperer la trame de retour renvoyer par le servomoteur + */ + + + // Wait for the bytes to be transmitted + wait (0.001); + + + + // Skip if the read was to the broadcast address + if (_ID != 0xFE) { + + + + /* Partie de reception de la trame de retour + */ + while ((flag_out != 1) && (timeout < (1000*bytes))) + { + // Les differents etats de l'automate on été créés au debut de la fonction write ! + switch (etat) + { + case Header1: if (_ax12.readable()) // reception du premier Header ( 0xFF ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == 0xFF ) + { + etat = Header2; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else etat = Header1; + } + else timeout++; + break; + + + case Header2: if (_ax12.readable()) // reception du second Header ( 0xFF ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == 0xFF ) + { + etat = ident; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else if (Status[plen] == ID ) // PERMET D'EVITER CERTAINES ERREUR LORSQU'ON LIT PLUSIEURS REGISTRES !!!! + { + Status[plen] = 0; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + Status[plen] = ID; + etat = length; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else + { + + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case ident: if (_ax12.readable()) // reception de l'octet correspondant à l'ID du servomoteur + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == ID ) + { + etat = length; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else + { + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case length: if (_ax12.readable()) // reception de l'octet correspondant à la taille ( taille = 2 + nombre de paramètres ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == (bytes+2) ) + { + etat = erreur; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else + { + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case erreur: if (_ax12.readable()) //reception de l'octet correspondant au code d'erreurs eventuels ( 0 = pas d'erreur ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + etat = reception; + } + else timeout++; + + case reception: while ( enable < bytes ) // reception du ou des octect(s) de donnés ( suivant la valeur de la variable length ) + { + if (_ax12.readable()) + { + Status[plen] = _ax12.getc(); + timeout = 0; + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + enable++; + + } + else timeout++; + } + etat = checksum; + break; + + case checksum: if (_ax12.readable()) // reception du dernier octet ( Checksum ) >>> checksum = NOT ( ID + length + somme des données ) >>>> dans le cas d'un retour d'un read!! + { + Status[plen] = _ax12.getc(); + timeout = 0; + flag_out = 1; + etat = Header1; + + #ifdef AX12_DEBUG_READ + printf("data[%d] : %d\r\n\n", plen, (int)Status[plen]); + #endif + } + else timeout++; + break; + + default: break; + } + } + + + if (timeout == (1000*bytes) ) // permet d'afficher si il y a une erreur de timeout et de ne pas rester bloquer si il y a des erreurs de trames + { + #ifdef AX12_DEBUG + printf ("timeout erreur\n"); + #endif + return(-1); + } + + + // copie des données dans le tableau data + for (int i=0; i < Status[3]-2 ; i++) + { + data[i] = Status[5+i]; + } + + } // toute la partie precedente ne s'effectue pas dans le cas d'un appel avec un broadcast ID (ID!=0xFE) + + return(Status[4]); // retourne le code d'erreur ( octect 5 de la trame de retour ) +} + +void AX12::multiple_goal_and_speed(int number_ax12,char* tab) +{ + char TxBuf[50]; + char sum = 0; + int timeout_transmit =0; + int i=0, k=0, j=0; + int L=4; // nombre instructions par paquets + int bytes= ((L+1)*number_ax12)+4; + + typedef enum {Header1, Header2, ident, length, erreur, checksum} type_etat; + type_etat etat= Header1; + + for(j=0; j<50; j++) + { + TxBuf[i]=0; + } + + #ifdef AX12_WRITE_DEBUG + //printf(" MULTIPLE_GOAL_AND_SPEED \n "); + #endif + +// Build the TxPacket first in RAM, then we'll send in one go + #ifdef AX12_WRITE_DEBUG + //printf("\nInstruction Packet\n Header :%d, %d\n",TxBuf[0], TxBuf[1]); + #endif + + TxBuf[0]=0xFF; // bit de start + TxBuf[1]=0xFF; // bit de start + + TxBuf[2] = 0xFE; //ID broadcast + sum += TxBuf[2]; + + #ifdef AX12_WRITE_DEBUG + printf(" adresse de difusion : %d\n",TxBuf[2]); + #endif + + TxBuf[3] =bytes; // longueur + sum += TxBuf[3]; + + #ifdef AX12_WRITE_DEBUG + printf(" Longueur : %d\n",TxBuf[3]); + #endif + + TxBuf[4]=0x83; //SYNC_WRITE + sum += TxBuf[4]; + + #ifdef AX12_WRITE_DEBUG + printf(" Instruction : 0x%x\n",TxBuf[4]); + #endif + + TxBuf[5] = 0x1E; // addresse "GOAL_POSITION" + sum += TxBuf[5]; + + #ifdef AX12_WRITE_DEBUG + printf(" Adresse de debut : 0x%x\n",TxBuf[5]); + #endif + + TxBuf[6]=L; // Nombre instruction par paquets + sum += TxBuf[6]; + + #ifdef AX12_WRITE_DEBUG + printf(" nombre instruction/paquet : 0x%x\n",TxBuf[6]); + #endif + + for(i=0; i<(number_ax12*5); i++) // Copie des data de TAB sur TxBuf + { + + TxBuf[i+7]=tab[i]; + sum += TxBuf[i+7]; + + } + + #ifdef AX12_WRITE_DEBUG + for(i=0; i<(number_ax12*5); i++) + { + + printf(" Data : 0x%x\n",TxBuf[i+7]); + + } + #endif + + TxBuf[(number_ax12*5)+7] = 0xFF - sum ; // CHECKSUM + + #ifdef AX12_WRITE_DEBUG + printf(" Checksum : 0x%x\n",TxBuf[(number_ax12*5)+9]); + #endif + + for(k=0; k<((number_ax12*5)+8); k++) // TRANSMISSION DE LA TRAME + { + _ax12.putc(TxBuf[k]); + #ifdef AX12_WRITE_DEBUG + printf(" transmission : 0x%x\n",TxBuf[k]); + #endif + } + + +} + +float AX12::read_and_test(float angle,char* Tab) +{ + int k=0; + unsigned short val_angle=0, val_reche=0; + + #ifdef AX12_DEBUG + printf("\nread_and_test"); + #endif + + if( _ID==0x12) + { k=1;} + else if( _ID==0x04) + { k=6;} + else if( _ID==0x07) + { k=11;} + else if( _ID==0x0F) + { k=16;} + + val_angle = (unsigned short) (angle/0.3); + val_reche = (unsigned short) Tab[k] + ((unsigned short)Tab[k+1]<<8); + + if((val_angle < (val_reche+(28))) && (val_angle > (val_reche-(28)))) + { + #ifdef AX12_DEBUG + printf("\nreturn1"); + #endif + return 1; + } + else + { + #ifdef AX12_DEBUG + printf("\nreturn0"); + #endif + return 0; + } + +} + +int AX12::write(int ID, int start, int bytes, char* data, int flag) +{ +// 0xff, 0xff, ID, Length, Intruction(write), Address, Param(s), Checksum + + char TxBuf[16]; + char sum = 0; + char Status[6]; + + int timeout = 0; + int plen = 0; + int flag_out = 0; + int timeout_transmit = 0; + int i = 0; + int poubelle = 0; + int count = 0; + char vidage[50]; + + typedef enum {Header1, Header2, ident, length, erreur, checksum} type_etat; + type_etat etat = Header1; + +#ifdef AX12_WRITE_DEBUG + printf("\nwrite(%d,0x%x,%d,data,%d)\n",ID,start,bytes,flag); +#endif + + // Build the TxPacket first in RAM, then we'll send in one go +#ifdef AX12_WRITE_DEBUG + printf("\nInstruction Packet\n Header : 0xFF, 0xFF\n"); +#endif + + TxBuf[0] = 0xff; + TxBuf[1] = 0xff; + + // ID + TxBuf[2] = ID; + sum += TxBuf[2]; + +#ifdef AX12_WRITE_DEBUG + printf(" ID : %d\n",TxBuf[2]); +#endif + + // packet Length + TxBuf[3] = 3+bytes; + sum += TxBuf[3]; + +#ifdef AX12_WRITE_DEBUG + printf(" Length : %d\n",TxBuf[3]); +#endif + + // Instruction + if (flag == 1) { + TxBuf[4]=0x04; + sum += TxBuf[4]; + } else { + TxBuf[4]=0x03; + sum += TxBuf[4]; + } + +#ifdef AX12_WRITE_DEBUG + printf(" Instruction : 0x%x\n",TxBuf[4]); +#endif + + // Start Address + TxBuf[5] = start; + sum += TxBuf[5]; + +#ifdef AX12_WRITE_DEBUG + printf(" Start : 0x%x\n",TxBuf[5]); +#endif + + // data + for (char i=0; i<bytes ; i++) { + TxBuf[6+i] = data[i]; + sum += TxBuf[6+i]; + +#ifdef AX12_WRITE_DEBUG + printf(" Data : 0x%x\n",TxBuf[6+i]); +#endif + + } + + // checksum + TxBuf[6+bytes] = 0xFF - sum; + +#ifdef AX12_WRITE_DEBUG + printf(" Checksum : 0x%x\n",TxBuf[6+bytes]); +#endif + + + /* Transmission de la trame construite precedemment dans le tableau TxBuf + */ + while ((timeout_transmit<100) && (i < (7+bytes))) + { + if (_ax12.writeable()) + { + _ax12.putc(TxBuf[i]); + i++; + timeout_transmit = 0; + } + else timeout_transmit++; + } + + if (timeout_transmit == 100 ) // dans le cas d'une sortie en timeout pour ne pas rester bloquer ! + { + #ifdef AX12_DEBUG + printf ("TIMEOUT TRANSMIT ERROR\r\n"); + #endif + return(-1); + } + /* Transmission effectuée on va ensuite récuperer la trame de retour renvoyer par le servomoteur + */ + + + // Wait for data to transmit + wait (0.005); + + // make sure we have a valid return + Status[4]=0x00; + + // we'll only get a reply if it was not broadcast + if (_ID!=0xFE) { + + + /* Partie de reception de la trame de retour + */ + while ((flag_out != 1) && (timeout < MAX_TIMEOUT)) + { + // Les differents etats de l'automate on été créés au debut de la fonction write ! + switch (etat) + { + case Header1: if (_ax12.readable()) // reception du premier Header ( 0xFF ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == 0xFF ) + { + etat = Header2; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + + } + else etat = Header1; + } + else timeout++; + break; + + + case Header2: if (_ax12.readable()) // reception du second Header ( 0xFF ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == 0xFF ) + { + etat = ident; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + } + else + { + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case ident: if (_ax12.readable()) // reception de l'octet correspondant à l'ID du servomoteur + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == ID ) + { + etat = length; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + } + else + { + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case length: if (_ax12.readable()) // reception de l'octet correspondant à la taille ( taille = 2 + nombre de paramètres ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + if (Status[plen] == 2 ) // dans la trame de retour d'un write il n'y a pas de paramètre la taille vaudra donc 2!! + { + etat = erreur; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + } + else + { + etat = Header1; + plen = 0; + } + } + else timeout++; + break; + + case erreur: if (_ax12.readable()) //reception de l'octet correspondant au code d'erreurs eventuels ( 0 = pas d'erreur ) + { + Status[plen] = _ax12.getc(); + timeout = 0; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + plen++; + etat = checksum; + } + else timeout++; + + case checksum: if (_ax12.readable()) // recpetion du dernier octet ( Checksum ) >>> checksum = NOT ( ID + length ) >>>> dans le cas de la reception d'un write + { + Status[plen] = _ax12.getc(); + timeout = 0; + flag_out = 1; + etat = Header1; + #ifdef AX12_DEBUG_WRITE + printf("data[%d] : %d\r\n\n", plen, (int)Status[plen]); + #endif + } + else timeout++; + break; + } + } + + + if ( Status[4] != 0 ) + { + #ifdef AX12_DEBUG + printf ("erreur ! \r\n"); + #endif + for (int i = 0; i<5; i++) + { + #ifdef AX12_DEBUG + printf("data[%d] : %d\r\n", plen, (int)Status[plen]); + #endif + } + } + + if (timeout == MAX_TIMEOUT ) // permet d'afficher si il y a une erreur de timeout et de ne pas rester bloquer si il y a des erreurs de trames + { + #ifdef AX12_DEBUG + printf ("timeout erreur\n\r"); + #endif + return(-1); + } + + // Build the TxPacket first in RAM, then we'll send in one go + } + + return(Status[4]); // retourne le code d'erreur ( octect 5 de la trame de retour ) +}
diff -r 000000000000 -r 80df663dd15e AX12/AX12.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/AX12/AX12.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,428 @@ +/* mbed AX-12+ Servo Library + * + * Copyright (c) 2010, cstyles (http://mbed.org) + * + * 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 MBED_AX12_H +#define MBED_AX12_H +#include "SerialHalfDuplex.h" +#include "mbed.h" + +//#define AX12_WRITE_DEBUG 0 +#define AX12_READ_DEBUG +//#define AX12_TRIGGER_DEBUG 0 +#define AX12_DEBUG 0 + +/****** à utiliser pour le debug !! ******/ + +//#define AX12_DEBUG_WRITE 0 +//#define AX12_DEBUG_READ 0 + +/******************************************/ + + +#define AX12_REG_ID 0x03 +#define AX12_REG_BAUD 0x04 +#define AX12_REG_DELAY_TIME 0x05 +#define AX12_REG_CW_LIMIT 0x06 +#define AX12_REG_CCW_LIMIT 0x08 +#define AX12_REG_TEMP_MAX 0x0B +#define AX12_REG_LOWEST_VOLTAGE 0x0C +#define AX12_REG_HIGHEST_VOLTAGE 0x0D +#define AX12_REG_MAX_TORQUE 0x0E +#define AX12_REG_SATUS_RETURN 0x10 +#define AX12_REG_ALARM_LED 0x11 +#define AX12_REG_ALARM_SHUTDOWN 0x12 +#define AX12_REG_DOWN_CALIBRATION 0x14 +#define AX12_REG_UP_CALIBRATION 0x16 +#define AX12_REG_TORQUE_ENABLE 0x18 +#define AX12_REG_LED 0x19 +#define AX12_REG_CW_MARGIN 0x1A +#define AX12_REG_CCW_MARGIN 0x1B +#define AX12_REG_CW_SLOPE 0x1C +#define AX12_REG_CCW_SLOPE 0x1D +#define AX12_REG_GOAL_POSITION 0x1E +#define AX12_REG_MOVING_SPEED 0x20 +#define AX12_REG_TORQUE_LIMIT 0x22 +#define AX12_REG_POSITION 0x24 +#define AX12_REG_PRESENT_SPEED 0x26 +#define AX12_REG_PRESENT_LOAD 0x28 +#define AX12_REG_VOLTS 0x2A +#define AX12_REG_TEMP 0x2B +#define AX12_REG_INSTRUCTION 0x2C +#define AX12_REG_MOVING 0x2E +#define AX12_REG_LOCK 0x2F +#define AX12_REG_PUNCH 0x30 + + +#define AX12_MODE_POSITION 0 +#define AX12_MODE_ROTATION 1 + +#define AX12_CW 1 +#define AX12_CCW 0 + +//--- Instruction --- +#define INST_PING 0x01 +#define INST_READ 0x02 +#define INST_WRITE 0x03 +#define INST_REG_WRITE 0x04 +#define INST_ACTION 0x05 +#define INST_RESET 0x06 +#define INST_DIGITAL_RESET 0x07 +#define INST_SYSTEM_READ 0x0C +#define INST_SYSTEM_WRITE 0x0D +#define INST_SYNC_WRITE 0x83 +#define INST_SYNC_REG_WRITE 0x84 + +#define DEFAULT_RETURN_PACKET_SIZE 6 + +#define BROADCASTING_ID 0xfe + +/** Servo control class, based on a PwmOut + * + * Example: + * @code + * #include "mbed.h" + * #include "AX12.h" + * + * int main() { + * + * AX12 myax12 (p9, p10, 1); + * + * while (1) { + * myax12.SetGoal(0); // go to 0 degrees + * wait (2.0); + * myax12.SetGoal(300); // go to 300 degrees + * wait (2.0); + * } + * } + * @endcode + */ +class AX12 +{ + +public: + + /** Create an AX12 servo object connected to the specified serial port, with the specified ID + * + * @param pin tx pin + * @param pin rx pin + * @param int ID, the Bus ID of the servo 1-255 + */ + AX12(PinName tx, PinName rx, int ID, int baud=1000000); + + /** Nouvelle fonction de commande de position du servomoteur avec sécurité d'arriver à la bonne position + Si une erreur se produit et que le servo ne recoit vraiment rien cette fonction dispose d'une sortie en timeout error; + */ + int Set_Secure_Goal(int degres); + + /** Retourne le temps d'attente avant l'envoi de la trame de retour par l'actionneur ( en micro seconde ) + */ + int Get_Return_Delay_Time(void); + + + /** Retourne la vitesse de communication de l'actionneur ( en Bits/seconde ) + */ + int Get_Baud_Rate(void); + + + /** Reglage du courant minimum necessaire au bon fonctionnement de l'actionneur + // minimum >> Ox000 >> decimal 0 + // maximum >> 0x3FF >> decimal 1023 + // deflaut >> 0x20 >> decimal 32 + */ + int Set_Punch(int punch); + + + /** Retourne le courant minimum au fonctionnement de l'actionneur + */ + int Get_Punch (void); + + + /** Retourne l'ampleur de la charge sur l'actionneur + */ + int Get_Load_Value (void); + + void read_all_info(unsigned char, unsigned char); + + /** Reset + */ + int Reset(int); + + /** Retourne la direction de la charge sur l'actionneur + */ + int Get_Load_Direction (void); + + + /** Retourne la vitesse angulaire actuelle de l'actionneur + */ + int Get_Present_Speed (void); + + + /** Retourne la valeur en degres du registre CCW angle limit qui est l'angle limite maximum de l'actionneur + */ + int Get_CCW_Angle_Limit (void); + + + /** Retourne la valeur en degres du registre CW angle limit qui est l'angle limite minimum de l'actionneur + */ + int Get_CW_Angle_Limit (void); + + + /** Retourne la valeur du registre Torque Enable + */ + int Get_Torque_Enable(void); + + + /** + 1 >>> + 0 >>> + */ + int Set_Torque_Enable(int etat); + + + /** Retourne les données de compensation des différences entre les potentiomètres + utilisés dans l'AX12 (Up) ???????? + */ + int Get_Up_Calibration (void); + + + /** Retourne les données de compensation des différences entre les potentiomètres + utilisés dans l'AX12 (Dowm) ???????? + */ + int Get_Down_Calibration(void); + + + /** Retourne l'ID de l'AX_12 avec lequel on dialogue + utile seulement dans le cas d'un broadcast ID + */ + int Get_ID(void); + + + /** Reglage du couple maximum de l'actionneur + // minimum >> Ox000 >> decimal 0 + // maximum >> 0x3FF >> decimal 1023 + // deflaut >> >> decimal + */ + int Set_Max_Torque(int torque); + + + /** Reglage de la desactivation des actionneurs si une erreur le concernant se produit + Bit Function + Bit 7 0 + Bit 6 If set to 1, torque off when an Instruction Error occurs + Bit 5 If set to 1, torque off when an Overload Error occurs + Bit 4 If set to 1, torque off when a Checksum Error occurs + Bit 3 If set to 1, torque off when a Range Error occurs + Bit 2 If set to 1, torque off when an Overheating Error occurs + Bit 1 If set to 1, torque off when an Angle Limit Error occurs + Bit 0 If set to 1, torque off when an Input Voltage Error occurs + */ + int Set_Alarm_Shutdown(int valeur); + + + /** Reglage de l'activation de l'alarme + Bit Function + Bit 7 0 + Bit 6 If set to 1, the LED blinks when an Instruction Error occurs + Bit 5 If set to 1, the LED blinks when an Overload Error occurs + Bit 4 If set to 1, the LED blinks when a Checksum Error occurs + Bit 3 If set to 1, the LED blinks when a Range Error occurs + Bit 2 If set to 1, the LED blinks when an Overheating Error occurs + Bit 1 If set to 1, the LED blinks when an Angle Limit Error occurs + Bit 0 If set to 1, the LED blinks when an Input Voltage Error occurs + */ + int Set_Alarm_LED(int valeur); + + + /** Reglage de la réponse à une instruction + * @param mode + * 0 >> ne repond a aucune instructions + * 1 >> repond seulement aux instructions READ_DATA + * 2 >> repond à toutes les instructions + */ + int Set_Status_Return_Level(int etat); + + + /** Reglage de la tension minimale + * @param mode + * minimum >> 0x32 >> decimal 50 + * maximum >> 0xFA >> decimal 250 + * deflaut >> 0x3C >> decimal 60 + */ + int Set_Lowest_Voltage(int val_lowest_voltage); + + + /** Reglage de la tension maximale + * @param mode + * minimum >> Ox32 >> decimal 50 + * maximum >> 0xFA >> decimal 250 + * deflaut >> 0xBE >> decimal 190 + */ + int Set_Highest_Voltage(int val_highest_voltage); + + + // Reglage du return time delay EN MICRO SECONDE 2uSec * val_delay_time + // minimum >> 0 us + // maximum >> 508 us + // deflaut >> 125 us + int Set_Delay_Time (int val_delay_time ); + + + /** Set Highest Limit Temperature + * @param mode + * minimum >> Ox00 >> decimal 0 + * maximum >> 0x96 >> decimal 150 + */ + int Set_Temperature_Max (int val_temperature ); + + + + /** Set the state of LED + * @param mode + * 0 = off, default + * 1 = on + */ + int Set_Etat_LED(int etat); + + + + /** Set the mode of the servo + * @param mode + * 0 = Positional, default + * 1 = Continuous rotation + */ + int Set_Mode(int mode); + + /** Set baud rate of all attached servos + * @param mode + * 0x01 = 1,000,000 bps + * 0x03 = 500,000 bps + * 0x04 = 400,000 bps + * 0x07 = 250,000 bps + * 0x09 = 200,000 bps + * 0x10 = 115,200 bps + * 0x22 = 57,600 bps + * 0x67 = 19,200 bps + * 0xCF = 9,600 bp + */ + int Set_Baud(int baud); + + + /** Set goal angle in integer degrees, in positional mode + * + * @param degrees 0-300 + * @param flags, defaults to 0 + * flags[0] = blocking, return when goal position reached + * flags[1] = register, activate with a broadcast trigger + * + */ + int Set_Goal(int degrees, int flags = 0); + + int Set_Goal_speed(int degrees, int flags = 0); + + /** Set the speed of the servo in continuous rotation mode + * + * @param speed, -1.0 to 1.0 + * -1.0 = full speed counter clock wise + * 1.0 = full speed clock wise + */ + int Set_CR_Speed(float speed); + + + /** Permet de définir l'angle limite minimum de l'actionneur ( prend une valeur d'entrée en degres ) + // minimum >> 0° + // maximum >> 300° + // deflaut >> 0° + */ + int Set_CW_Angle_Limit(int degrees); + + /** Permet de définir l'angle limite maximum de l'actionneur ( prend une valeur d'entrée en degres ) + // minimum >> 0° + // maximum >> 300° + // deflaut >> 300° + */ + int Set_CCW_Angle_Limit(int degrees); + + // Change the ID + + /** Change the ID of a servo + * + * @param CurentID 1-255 + * @param NewID 1-255 + * + * If a servo ID is not know, the broadcast address of 0 can be used for CurrentID. + * In this situation, only one servo should be connected to the bus + */ + int Set_ID(int CurrentID, int NewID); + + + /** Poll to see if the servo is moving + * + * @returns true is the servo is moving + */ + int isMoving(void); + + /** Send the broadcast "trigger" command, to activate any outstanding registered commands + */ + void trigger(void); + + /** Send the "reset" command, to activate any outstanding registered commands + */ + void reset(); + + /** Read the current angle of the servo + * + * @returns float in the range 0.0-300.0 + */ + float Get_Position(); + + /** Read the temperature of the servo + * + * @returns float temperature + */ + float Get_Temp(void); + + /** Read the supply voltage of the servo + * + * @returns float voltage + */ + float Get_Volts(void); + + // Lecture du couple maximum ( retourne la valeur du registre Max Torque de l'AX12 ) + int Get_Max_Torque (void); + + + int read(int ID, int start, int length, char* data); + int write(int ID, int start, int length, char* data, int flag=0); + void multiple_goal_and_speed(int number_ax12,char* tab); + float read_and_test(float angle,char* Tab); + +private : + + SerialHalfDuplex _ax12; + int _ID; + int _baud; + + +}; + +#endif
diff -r 000000000000 -r 80df663dd15e ident_crac.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ident_crac.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,101 @@ +#define GLOBAL_GAME_END 0x004 // Stop fin du match +#define GLOBAL_START 0x002 // Start +#define GLOBAL_END_INIT_POSITION 0x005 // Fin positionnement robot avant depart +#define GLOBAL_FUNNY_ACTION 0x007 // Funny action start (0: start, 1: stop) + +#define BALISE_STOP 0x003 // Trame stop (angle en °, Type du robot : 1=>gros robot, 2=> petit) +#define BALISE_DANGER 0xA // Trame danger (angle en °, Type du robot : 1=>gros robot, 2=> petit) +#define BALISE_END_DANGER 0xB // Trame fin de danger + +#define ASSERVISSEMENT_STOP 0x001 // Stop moteur +#define ASSERVISSEMENT_SPEED_DANGER 0x006 // Vitesse de danger +#define ASSERVISSEMENT_XYT 0x020 // Asservissement (x,y,theta) (0 : au choix 1 : avant -1 : arrière) +#define ASSERVISSEMENT_COURBURE 0x021 // Asservissement rayon de courbure (+ gauche, - droite , sens : 1avt , -1arr; enchainement => 1 oui, 0 => non, 2=>derniére instruction de l'enchainement) +#define ASSERVISSEMENT_CONFIG 0x022 // Asservissement paramètre (définir les valeurs de vitesse max et d'eccélération max) +#define ASSERVISSEMENT_ROTATION 0x023 // Asservissement rotation +#define ASSERVISSEMENT_RECALAGE 0x024 // Moteur tout droit (recalage : 0 mouvement seul, 1 x, 2y valeur : coordonnée à laquelle est recalé x/y; enchainement => 1 oui, 0 => non) + +#define ODOMETRIE_BIG_POSITION 0x026 // Odométrie position robot (Position actuel du robot) +#define ODOMETRIE_BIG_VITESSE 0x027 // Odométrie vitesse (Indication sur l'état actuel) +#define ODOMETRIE_SMALL_POSITION 0x028 // Odométrie position robot (Position actuel du robot) +#define ODOMETRIE_SMALL_VITESSE 0x029 // Odométrie vitesse (Indication sur l'état actuel) + +#define ASSERVISSEMENT_INFO_CONSIGNE 0x1F0 // Info Consigne et Commande moteur +#define ASSERVISSEMENT_CONFIG_KPP_DROITE 0x1F1 // Config coef KPP_Droit +#define ASSERVISSEMENT_CONFIG_KPI_DROITE 0x1F2 // Config coef KPI_Droit +#define ASSERVISSEMENT_CONFIG_KPD_DROITE 0x1F3 // Config coef KPD_Droit +#define ASSERVISSEMENT_CONFIG_KPP_GAUCHE 0x1F4 // Config coef KPP_Gauche +#define ASSERVISSEMENT_CONFIG_KPI_GAUCHE 0x1F5 // Config coef KPI_Gauche +#define ASSERVISSEMENT_CONFIG_KPD_GAUCHE 0x1F6 // Config coef KPD_Gauche +#define ASSERVISSEMENT_ENABLE 0x1F7 // Activation asservissement (0 : désactivation, 1 : activation) + +#define RESET_BALISE 0x030 // Reset balise +#define RESET_MOTEUR 0x031 // Reset moteur +#define RESET_IHM 0x032 // Reset écran tactile +#define RESET_ACTIONNEURS 0x033 // Reset actionneurs +#define RESET_STRAT 0x3A // Reset stratégie + +#define CHECK_BALISE 0x060 // Check balise +#define CHECK_MOTEUR 0x061 // Check moteur +#define CHECK_IHM 0x062 // Check écran tactile +#define CHECK_ACTIONNEURS 0x063 // Check actionneurs +#define CHECK_POMPE 0x064 // Check de la pompe +#define CHECK_AX12 0x065 // Check des ax12 + +#define ALIVE_BALISE 0x070 // Alive balise +#define ALIVE_MOTEUR 0x071 // Alive moteur +#define ALIVE_IHM 0x072 // Alive écran tactile +#define ALIVE_ACTIONNEURS 0x073 // Alive actionneurs +#define ALIVE_AX12 0x075 //Alive AX12 + +#define SERVO_AX12_ACTION 0x96 //AX12 action +#define SERVO_AX12_ACK 0x106 //AX12 ACK +#define SERVO_AX12_END 0x116 //AX12 END action +#define SERVO_AX12_POSITION 0x126 //AX12_POSITION + +#define ACKNOWLEDGE_BALISE 0x100 // Acknowledge balise +#define ACKNOWLEDGE_MOTEUR 0x101 // Acknowledge moteur +#define ACKNOWLEDGE_IHM 0x102 // Acknowledge ecran tactile +#define ACKNOWLEDGE_ACTIONNEURS 0x103 // Acknowledge actionneurs + +#define INSTRUCTION_END_BALISE 0x110 // Fin instruction balise (Indique que l'instruction est terminée) +#define INSTRUCTION_END_MOTEUR 0x111 // Fin instruction moteur (Indique que l'instruction est terminée) +#define INSTRUCTION_END_IHM 0x112 // Fin instruction ecran tactile (Indique que l'instruction est terminée) +#define INSTRUCTION_END_ACTIONNEURS 0x113 // Fin instruction actionneurs (Indique que l'instruction est terminée) + +#define ECRAN_CHOICE_STRAT 0x601 // Choix d'une stratégie (n° strat (1-4)) +#define ECRAN_CHOICE_COLOR 0x602 // Couleur (0->Purple;1->green) +#define ECRAN_START_MATCH 0x603 // Match (Indique que l'on souhaite commencer le match) +#define ECRAN_DEMO_BEGIN 0x604 // Debut du mode Demonstration +#define ECRAN_ACK_STRAT 0x611 // Acknowledge stratégie (si 0 erreur, sinon n°strat) +#define ECRAN_ACK_COLOR 0x612 // Acknowledge couleur (0->Purple;1->green) +#define ECRAN_ACK_START_MATCH 0x613 // Acknowledge Match (Indique que l'on a bien reçu le debut du match) +#define ECRAN_ACK_DEMO 0x614 // Acknowledge Demonstration +#define ECRAN_ALL_CHECK 0x620 // Carte all check (Si provient de carte strat => toutes les cartes sont en ligne, Si provient IHM => forcer le lancement) +#define ECRAN_TIME 0x621 // Time match (Indication de moment cle du temps (10,30,60,70,80,85,90)) +#define ECRAN_PRINTF_1 0x6C0 // Tactile printf (Afficher les 8 permier caractères) +#define ECRAN_PRINTF_2 0x6C1 // Tactile printf (Afficher les 8 second caractères) +#define ECRAN_PRINTF_3 0x6C2 // Tactile printf (Afficher les 8 troisième caractères) +#define ECRAN_PRINTF_4 0x6C3 // Tactile printf (Afficher les 8 quatrième caractères) +#define ECRAN_PRINTF_CLEAR 0x6CF // Tactile printf clear (Permet d'effacer l'ecran) + +#define ERROR_OVERFLOW_BALISE 0x040 // Overflow odométrie +#define ERROR_OVERFLOW_MOTEUR 0x041 // Overflow asservissement +#define ERROR_OVERFLOW_IHM 0x042 // Overflow balise +#define ERROR_OVERFLOW_STRAT 0x043 // Overflow stratégie +#define ERROR_BALISE 0x785 // Bug balise +#define ERROR_RTC 0x786 // Bug RTC +#define ERROR_MOTEUR 0x787 // Bug moteur +#define ERROR_TELEMETRIE 0x788 // Bug télémètre +#define ERROR_STRATEGIE 0x789 // Bug stratégie + +#define DEBUG_STRATEGIE_AUTOMATE 0x760 // Etat automate stratégie (Permet de savoir l'etat de l'automate) +#define DEBUG_FAKE_JAKE 0x761 // Fake jack (Permet d'outre passerr le JACk du robot) +#define DEBUG_ASSERV 0x762 // Info debug carte moteur + +#define SERVO_AX12_SETGOAL 0x090 // AX12 setGoal (Indiquer la nouvelle position de l'AX12 !! Ne bouge pas) +#define SERVO_AX12_PROCESS 0x091 // AX12 processChange (Lancer le déplacement des AX12) +#define SERVO_AX12_DONE 0x092 // AX12 done (Indique q'un AX12 a terminé son déplacement) +#define SERVO_XL320 0x093 // XL320 +#define POMPE_PWM 0x9A // pwm des pompes +
diff -r 000000000000 -r 80df663dd15e main.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,391 @@ +/**************************************************************************************************/ +/* cette fonction de controle de l'MX12 est réalisée à partir de la même bibliothèque que les AX12*/ +/**************************************************************************************************/ + +#include "mbed.h" +#include "AX12.h" +#include "cmsis.h" +#include "ident_crac.h" + +#define AX12_INITIALISATION 0 +#define AX12_PREPARATION_PRISE 1 +#define AX12_STOCKAGE_HAUT 2 +#define AX12_STOCKAGE_BAS 3 +#define AX12_DEPOSER 4 +#define AX12_PREPARATION_DEPOT_BAS 5 +#define AX12_PREPARATION_DEPOT_HAUT 6 +#define AX12_POUSSER_MODULE 7 +#define AX12_DEFAUT 20 + +#define TIME 0.8 +#define TOLERANCE_AX12 50 +#define SIZE_FIFO 25 + + /* DECLARATION VARIABLES */ +CAN can1(p30,p29); +CANMessage msgRxBuffer[SIZE_FIFO]; +unsigned char FIFO_ecriture=0; //Position du fifo pour la reception CAN +unsigned char FIFO_lecture=0;//Position du fifo de lecture des messages CAN + +extern "C" void mbed_reset();//Pour pouvoir reset la carte + +unsigned char action = 0, choix_bras = 0, etat_ax12 = 0, flag = 0; +static float TAB_ANGLE1[4], TAB_ANGLE2[4]; +static char TAB_POSITION[4]; +short vitesse=700; +float angle=0.0; +float test_socle=0.0,test_bas=0.0,test_milieu=0.0,test_haut=0.0,test_ventouse=0.0, test_calcul=0.0, valeur_test=0.0; +AX12 *un_myMX12; + + + /* PROTOTYPES DE FONCTIONS ET POINTEURS */ + + +/****************************************************************************************/ +/* FUNCTION NAME: CAN2_wrFilter */ +/* DESCRIPTION : Fonction qui permet de ne garder que les ID qui nous interessent */ +/****************************************************************************************/ +void CAN2_wrFilter (uint32_t id); + +/****************************************************************************************/ +/* FUNCTION NAME: canProcessRx */ +/* DESCRIPTION : Fonction de traitement des messages CAN */ +/****************************************************************************************/ +void canProcessRx(void); + +/****************************************************************************************/ +/* FUNCTION NAME: canRx_ISR */ +/* DESCRIPTION : Interruption en réception sur le CAN */ +/****************************************************************************************/ +void canRx_ISR (void); + +/****************************************************************************************/ +/* FUNCTION NAME: SendRawId */ +/* DESCRIPTION : Fonction qui permet d'envoi une trame vide à un ID */ +/****************************************************************************************/ +void SendRawId (unsigned short id); + +/****************************************************************************************/ +/* FUNCTION NAME: Fin_action */ +/* DESCRIPTION : Fonction qui confirme la fin de mouvement des AX12 */ +/****************************************************************************************/ +void Fin_action(void); + +/****************************************************************************************/ +/* FUNCTION NAME: Automate_ax12 */ +/* DESCRIPTION : Fonction qui gère les différentes actions des AX12 */ +/****************************************************************************************/ +void AX12_automate(void); + +/****************************************************************************************/ +/* FUNCTION NAME: Initialisation */ +/* DESCRIPTION : Fonction qui place les bras en position verticale */ +/****************************************************************************************/ +void Initialisation(void); + +/****************************************************************************************/ +/* FUNCTION NAME: bouger_MX12 */ +/* DESCRIPTION : Fonction qui sélectionne le sens de rotation de l'MX12 et le bouge */ +/****************************************************************************************/ +void bouger_MX12(unsigned char choix); + +Timer t; +Ticker flipper; + + + /* ANGLE */ + +/* 0 = tourner à droite + 600 = position initiale + 1200 = tourner à gauche + */ + + /* NUMERO MX12 : 0x01 */ + + + /* MAIN */ + +int main() +{ + can1.frequency(1000000); // fréquence de travail 1Mbit/s + can1.attach(&canRx_ISR); // création de l'interrupt attachée à la réception sur le CAN + CAN2_wrFilter(SERVO_AX12_ACTION); // 0x96 Trie des messages CAN sur les paramètres suivants. + CAN2_wrFilter(SERVO_AX12_ACK); // 0x106 + CAN2_wrFilter(SERVO_AX12_END); // 0x116 + CAN2_wrFilter(CHECK_AX12); // 0x65 + + // Set l'ID du MX12 et la vitesse de communication. Paramètres : tx rx id baud + un_myMX12 = new AX12(p9, p10, 1, 1000000); //Trappe de fermeture du lanceur. + + while(true) { + AX12_automate();// Trie les actions de l'MX12 + canProcessRx(); // Traitement des trames CAN en attente + } +} + + /* FONCTIONS */ + +/****************************************************************************************/ +/* FUNCTION NAME: canProcessRx */ +/* DESCRIPTION : Fonction de traitement des messages CAN */ +/****************************************************************************************/ +void canProcessRx(void) +{ + static signed char FIFO_occupation=0,FIFO_max_occupation=0; + + CANMessage msgTx=CANMessage(); // Set la structure d'un message CAN Tx : id, data, taille, type, format + msgTx.format=CANStandard; + msgTx.type=CANData; + FIFO_occupation=FIFO_ecriture-FIFO_lecture; + + if(FIFO_occupation<0) + FIFO_occupation=FIFO_occupation+SIZE_FIFO; //Taille du CANRx. + + if(FIFO_max_occupation<FIFO_occupation) + FIFO_max_occupation=FIFO_occupation; + + if(FIFO_occupation!=0) { + + switch(msgRxBuffer[FIFO_lecture].id) { + case CHECK_AX12: // 0x065 + SendRawId(ALIVE_AX12); + flag = 1; + break; + + case SERVO_AX12_ACTION : // 0x96 + etat_ax12 = msgRxBuffer[FIFO_lecture].data[0]; + + //ACK de reception des actions a effectuer + msgTx.id = SERVO_AX12_ACK; + msgTx.len = 1; + msgTx.data[0] = msgRxBuffer[FIFO_lecture].data[0]; + can1.write(msgTx); + break; + } + + FIFO_lecture=(FIFO_lecture+1)%SIZE_FIFO; + } +} + +/****************************************************************************************/ +/* FUNCTION NAME: canRx_ISR */ +/* DESCRIPTION : Interruption en réception sur le CAN */ +/****************************************************************************************/ +void canRx_ISR (void) +{ + if (can1.read(msgRxBuffer[FIFO_ecriture])) { + if(msgRxBuffer[FIFO_ecriture].id==RESET_STRAT) mbed_reset(); + else FIFO_ecriture=(FIFO_ecriture+1)%SIZE_FIFO; + } +} + +/****************************************************************************************/ +/* FUNCTION NAME: SendRawId */ +/* DESCRIPTION : Fonction qui permet d'envoyer une trame vide à un ID */ +/****************************************************************************************/ +void SendRawId (unsigned short id) +{ + CANMessage msgTx=CANMessage(); + msgTx.id=id; + msgTx.len=0; + can1.write(msgTx); +} + + +/****************************************************************************************/ +/* FUNCTION NAME: Initialisation */ +/* DESCRIPTION : Place le MX12 en position initiale : lanceur fermé */ +/****************************************************************************************/ +void Initialisation(){ + un_myMX12-> Set_Goal_speed(vitesse); + un_myMX12-> Set_Mode(0); +} + +/****************************************************************************************/ +/* FUNCTION NAME: bouger_MX12 */ +/* DESCRIPTION : Fonction qui sélectionne le sens de rotation de l'MX12 et le bouge */ +/****************************************************************************************/ +void bouger_MX12(unsigned char choix){ + AX12 *ptr_myAX12; + ptr_myAX12 = new AX12(p9, p10, 1,1000000); // Create objects + if( choix == 1) // Tourne à droite + { + ptr_myAX12->Set_Secure_Goal(0); // tourner droite + } + else if(choix == 2) // Tourne à gauche + { + ptr_myAX12->Set_Secure_Goal(1200); // tourner gauche + } + else if (choix == 0) + { + ptr_myAX12->Set_Secure_Goal(600); // position initiale + } +} + +/****************************************************************************************/ +/* FUNCTION NAME: Fin_action */ +/* DESCRIPTION : Fonction qui confirme la fin de mouvement des AX12 */ +/****************************************************************************************/ +void Fin_action(void){ + CANMessage msgTx=CANMessage(); + msgTx.format=CANStandard; + msgTx.type=CANData; + + msgTx.id = SERVO_AX12_END; + msgTx.len = 1; + msgTx.data[0] = AX12_PREPARATION_PRISE; + can1.write(msgTx); // Envoie le message via le CAN. +} + +/****************************************************************************************/ +/* FUNCTION NAME: Automate_ax12 */ +/* DESCRIPTION : Fonction qui gère les différentes actions des AX12 */ +/****************************************************************************************/ +void AX12_automate(void){ + switch(etat_ax12){ + case AX12_INITIALISATION : // Etat = 0 + if (flag == 1){ // Décide si il faut initialiser le bras droit ou gauche + Initialisation(); + flag = 2; + } + break; + + case AX12_PREPARATION_PRISE : // Etat = 1 + bouger_MX12(msgRxBuffer[FIFO_lecture].data[1]); + if (action == 0){ + Fin_action(); + action ++; + } + break; + case AX12_DEFAUT : + action = 0; + break; + } +} + +/****************************************************************************************/ +/* FUNCTION NAME: CAN2_wrFilter */ +/* DESCRIPTION : Fonction qui permet de ne garder que les ID qui nous interessent */ +/****************************************************************************************/ +void CAN2_wrFilter (uint32_t id) { + static int CAN_std_cnt = 0; + uint32_t buf0, buf1; + int cnt1, cnt2, bound1; + + /* Acceptance Filter Memory full */ + if (((CAN_std_cnt + 1) >> 1) >= 512) + return; /* error: objects full */ + + /* Setup Acceptance Filter Configuration + Acceptance Filter Mode Register = Off */ + LPC_CANAF->AFMR = 0x00000001; + + id |= 1 << 13; /* Add controller number(2) */ + id &= 0x0000F7FF; /* Mask out 16-bits of ID */ + + if (CAN_std_cnt == 0) { /* For entering first ID */ + LPC_CANAF_RAM->mask[0] = 0x0000FFFF | (id << 16); + } else if (CAN_std_cnt == 1) { /* For entering second ID */ + if ((LPC_CANAF_RAM->mask[0] >> 16) > id) + LPC_CANAF_RAM->mask[0] = (LPC_CANAF_RAM->mask[0] >> 16) | (id << 16); + else + LPC_CANAF_RAM->mask[0] = (LPC_CANAF_RAM->mask[0] & 0xFFFF0000) | id; + } else { + /* Find where to insert new ID */ + cnt1 = 0; + cnt2 = CAN_std_cnt; + bound1 = (CAN_std_cnt - 1) >> 1; + while (cnt1 <= bound1) { /* Loop through standard existing IDs */ + if ((LPC_CANAF_RAM->mask[cnt1] >> 16) > id) { + cnt2 = cnt1 * 2; + break; + } + if ((LPC_CANAF_RAM->mask[cnt1] & 0x0000FFFF) > id) { + cnt2 = cnt1 * 2 + 1; + break; + } + cnt1++; /* cnt1 = U32 where to insert new ID */ + } /* cnt2 = U16 where to insert new ID */ + + if (cnt1 > bound1) { /* Adding ID as last entry */ + if ((CAN_std_cnt & 0x0001) == 0) /* Even number of IDs exists */ + LPC_CANAF_RAM->mask[cnt1] = 0x0000FFFF | (id << 16); + else /* Odd number of IDs exists */ + LPC_CANAF_RAM->mask[cnt1] = (LPC_CANAF_RAM->mask[cnt1] & 0xFFFF0000) | id; + } else { + buf0 = LPC_CANAF_RAM->mask[cnt1]; /* Remember current entry */ + if ((cnt2 & 0x0001) == 0) /* Insert new mask to even address */ + buf1 = (id << 16) | (buf0 >> 16); + else /* Insert new mask to odd address */ + buf1 = (buf0 & 0xFFFF0000) | id; + + LPC_CANAF_RAM->mask[cnt1] = buf1; /* Insert mask */ + + bound1 = CAN_std_cnt >> 1; + /* Move all remaining standard mask entries one place up */ + while (cnt1 < bound1) { + cnt1++; + buf1 = LPC_CANAF_RAM->mask[cnt1]; + LPC_CANAF_RAM->mask[cnt1] = (buf1 >> 16) | (buf0 << 16); + buf0 = buf1; + } + + if ((CAN_std_cnt & 0x0001) == 0) /* Even number of IDs exists */ + LPC_CANAF_RAM->mask[cnt1] = (LPC_CANAF_RAM->mask[cnt1] & 0xFFFF0000) | (0x0000FFFF); + } + } + CAN_std_cnt++; + + /* Calculate std ID start address (buf0) and ext ID start address <- none (buf1) */ + buf0 = ((CAN_std_cnt + 1) >> 1) << 2; + buf1 = buf0; + + /* Setup acceptance filter pointers */ + LPC_CANAF->SFF_sa = 0; + LPC_CANAF->SFF_GRP_sa = buf0; + LPC_CANAF->EFF_sa = buf0; + LPC_CANAF->EFF_GRP_sa = buf1; + LPC_CANAF->ENDofTable = buf1; + + LPC_CANAF->AFMR = 0x00000000; /* Use acceptance filter */ +} // CAN2_wrFilter + +/****************************************************************************************/ +/* FUNCTION NAME: Check_positionAX12 */ +/* DESCRIPTION : Fonction qui permet de verifier la position de l'MX12 */ +/****************************************************************************************/ +void Check_positionAX12(char* TAB, unsigned char choix){ + static float TAB_POS_TH[4]; + + CANMessage msgTx=CANMessage(); + msgTx.id=SERVO_AX12_POSITION; + msgTx.len=5; + + //PERMET DE VERIFIER LA POSITION De l'MX12 + TAB_ANGLE1[0] = (unsigned short)(un_myMX12->Get_Position()/0.3); + + + TAB_POS_TH[0] = (unsigned short) TAB[0] + ((unsigned short)TAB[1]<<8); + + if (choix == 1){ + if ((TAB_ANGLE1[0] < TAB_POS_TH[0]+TOLERANCE_AX12) && (TAB_ANGLE1[0] > TAB_POS_TH[0]-TOLERANCE_AX12)){ + TAB_POSITION[0] = 1; + } + else if ((TAB_ANGLE1[0] < TAB_POS_TH[0]+TOLERANCE_AX12) && (TAB_ANGLE1[0] > TAB_POS_TH[0]-TOLERANCE_AX12)){ + TAB_POSITION[0] = 0; + } + } + else if (choix == 2){ + if ((TAB_ANGLE2[0] < TAB_POS_TH[0]+TOLERANCE_AX12) && (TAB_ANGLE2[0] > TAB_POS_TH[0]-TOLERANCE_AX12)){ + TAB_POSITION[0] = 1; + } + else if ((TAB_ANGLE2[0] < TAB_POS_TH[0]+TOLERANCE_AX12) && (TAB_ANGLE2[0] > TAB_POS_TH[0]-TOLERANCE_AX12)){ + TAB_POSITION[0] = 0; + } + } + + msgTx.data[0] = choix; + msgTx.data[0] = TAB_POSITION[0]; + can1.write(msgTx); +} + \ No newline at end of file
diff -r 000000000000 -r 80df663dd15e mbed/AnalogIn.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/AnalogIn.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,99 @@ +/* mbed Microcontroller Library - AnalogIn + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_ANALOGIN_H +#define MBED_ANALOGIN_H + +#include "device.h" + +#if DEVICE_ANALOGIN + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: AnalogIn + * An analog input, used for reading the voltage on a pin + * + * Example: + * > // Print messages when the AnalogIn is greater than 50% + * > + * > #include "mbed.h" + * > + * > AnalogIn temperature(p20); + * > + * > int main() { + * > while(1) { + * > if(temperature > 0.5) { + * > printf("Too hot! (%f)", temperature.read()); + * > } + * > } + * > } + */ +class AnalogIn : public Base { + +public: + + /* Constructor: AnalogIn + * Create an AnalogIn, connected to the specified pin + * + * Variables: + * pin - AnalogIn pin to connect to + * name - (optional) A string to identify the object + */ + AnalogIn(PinName pin, const char *name = NULL); + + /* Function: read + * Read the input voltage, represented as a float in the range [0.0, 1.0] + * + * Variables: + * returns - A floating-point value representing the current input voltage, + * measured as a percentage + */ + float read(); + + /* Function: read_u16 + * Read the input voltage, represented as an unsigned short in the range [0x0, 0xFFFF] + * + * Variables: + * returns - 16-bit unsigned short representing the current input voltage, + * normalised to a 16-bit value + */ + unsigned short read_u16(); + +#ifdef MBED_OPERATORS + /* Function: operator float + * An operator shorthand for <read()> + * + * The float() operator can be used as a shorthand for <read()> to simplify common code sequences + * + * Example: + * > float x = volume.read(); + * > float x = volume; + * > + * > if(volume.read() > 0.25) { ... } + * > if(volume > 0.25) { ... } + */ + operator float(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + ADCName _adc; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/AnalogOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/AnalogOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,112 @@ +/* mbed Microcontroller Library - AnalogOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_ANALOGOUT_H +#define MBED_ANALOGOUT_H + +#include "device.h" + +#if DEVICE_ANALOGOUT + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: AnalogOut + * An analog output, used for setting the voltage on a pin + * + * Example: + * > // Make a sawtooth output + * > + * > #include "mbed.h" + * > + * > AnalogOut tri(p18); + * > int main() { + * > while(1) { + * > tri = tri + 0.01; + * > wait_us(1); + * > if(tri == 1) { + * > tri = 0; + * > } + * > } + * > } + */ +class AnalogOut : public Base { + +public: + + /* Constructor: AnalogOut + * Create an AnalogOut connected to the specified pin + * + * Variables: + * pin - AnalogOut pin to connect to (18) + */ + AnalogOut(PinName pin, const char *name = NULL); + + /* Function: write + * Set the output voltage, specified as a percentage (float) + * + * Variables: + * percent - A floating-point value representing the output voltage, + * specified as a percentage. The value should lie between + * 0.0f (representing 0v / 0%) and 1.0f (representing 3.3v / 100%). + * Values outside this range will be saturated to 0.0f or 1.0f. + */ + void write(float value); + + /* Function: write_u16 + * Set the output voltage, represented as an unsigned short in the range [0x0, 0xFFFF] + * + * Variables: + * value - 16-bit unsigned short representing the output voltage, + * normalised to a 16-bit value (0x0000 = 0v, 0xFFFF = 3.3v) + */ + void write_u16(unsigned short value); + + /* Function: read + * Return the current output voltage setting, measured as a percentage (float) + * + * Variables: + * returns - A floating-point value representing the current voltage being output on the pin, + * measured as a percentage. The returned value will lie between + * 0.0f (representing 0v / 0%) and 1.0f (representing 3.3v / 100%). + * + * Note: + * This value may not match exactly the value set by a previous <write>. + */ + float read(); + + +#ifdef MBED_OPERATORS + /* Function: operator= + * An operator shorthand for <write()> + */ + AnalogOut& operator= (float percent); + AnalogOut& operator= (AnalogOut& rhs); + + /* Function: operator float() + * An operator shorthand for <read()> + */ + operator float(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + DACName _dac; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/Base.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Base.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,225 @@ +/* mbed Microcontroller Library - Base + * Copyright (c) 2006-2008 ARM Limited. All rights reserved. + */ + +#ifndef MBED_BASE_H +#define MBED_BASE_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include <cstdlib> +#include "DirHandle.h" + +namespace mbed { + +#ifdef MBED_RPC +struct rpc_function { + const char *name; + void (*caller)(const char*, char*); +}; + +struct rpc_class { + const char *name; + const rpc_function *static_functions; + struct rpc_class *next; +}; +#endif + +/* Class Base + * The base class for most things + */ +class Base { + +public: + + Base(const char *name = NULL); + + virtual ~Base(); + + /* Function register_object + * Registers this object with the given name, so that it can be + * looked up with lookup. If this object has already been + * registered, then this just changes the name. + * + * Variables + * name - The name to give the object. If NULL we do nothing. + */ + void register_object(const char *name); + + /* Function name + * Returns the name of the object, or NULL if it has no name. + */ + const char *name(); + +#ifdef MBED_RPC + + /* Function rpc + * Call the given method with the given arguments, and write the + * result into the string pointed to by result. The default + * implementation calls rpc_methods to determine the supported + * methods. + * + * Variables + * method - The name of the method to call. + * arguments - A list of arguments separated by spaces. + * result - A pointer to a string to write the result into. May + * be NULL, in which case nothing is written. + * + * Returns + * true if method corresponds to a valid rpc method, or + * false otherwise. + */ + virtual bool rpc(const char *method, const char *arguments, char *result); + + /* Function get_rpc_methods + * Returns a pointer to an array describing the rpc methods + * supported by this object, terminated by either + * RPC_METHOD_END or RPC_METHOD_SUPER(Superclass). + * + * Example + * > class Example : public Base { + * > int foo(int a, int b) { return a + b; } + * > virtual const struct rpc_method *get_rpc_methods() { + * > static const rpc_method rpc_methods[] = { + * > { "foo", generic_caller<int, Example, int, int, &Example::foo> }, + * > RPC_METHOD_SUPER(Base) + * > }; + * > return rpc_methods; + * > } + * > }; + */ + virtual const struct rpc_method *get_rpc_methods(); + + /* Function rpc + * Use the lookup function to lookup an object and, if + * successful, call its rpc method + * + * Variables + * returns - false if name does not correspond to an object, + * otherwise the return value of the call to the object's rpc + * method. + */ + static bool rpc(const char *name, const char *method, const char *arguments, char *result); + +#endif + + /* Function lookup + * Lookup and return the object that has the given name. + * + * Variables + * name - the name to lookup. + * len - the length of name. + */ + static Base *lookup(const char *name, unsigned int len); + + static DirHandle *opendir(); + friend class BaseDirHandle; + +protected: + + static Base *_head; + Base *_next; + const char *_name; + bool _from_construct; + +private: + +#ifdef MBED_RPC + static rpc_class *_classes; + + static const rpc_function _base_funcs[]; + static rpc_class _base_class; +#endif + + void delete_self(); + static void list_objs(const char *arguments, char *result); + static void clear(const char*,char*); + + static char *new_name(Base *p); + +public: + +#ifdef MBED_RPC + /* Function add_rpc_class + * Add the class to the list of classes which can have static + * methods called via rpc (the static methods which can be called + * are defined by that class' get_rpc_class() static method). + */ + template<class C> + static void add_rpc_class() { + rpc_class *c = C::get_rpc_class(); + c->next = _classes; + _classes = c; + } + + template<class C> + static const char *construct() { + Base *p = new C(); + p->_from_construct = true; + if(p->_name==NULL) { + p->register_object(new_name(p)); + } + return p->_name; + } + + template<class C, typename A1> + static const char *construct(A1 arg1) { + Base *p = new C(arg1); + p->_from_construct = true; + if(p->_name==NULL) { + p->register_object(new_name(p)); + } + return p->_name; + } + + template<class C, typename A1, typename A2> + static const char *construct(A1 arg1, A2 arg2) { + Base *p = new C(arg1,arg2); + p->_from_construct = true; + if(p->_name==NULL) { + p->register_object(new_name(p)); + } + return p->_name; + } + + template<class C, typename A1, typename A2, typename A3> + static const char *construct(A1 arg1, A2 arg2, A3 arg3) { + Base *p = new C(arg1,arg2,arg3); + p->_from_construct = true; + if(p->_name==NULL) { + p->register_object(new_name(p)); + } + return p->_name; + } + + template<class C, typename A1, typename A2, typename A3, typename A4> + static const char *construct(A1 arg1, A2 arg2, A3 arg3, A4 arg4) { + Base *p = new C(arg1,arg2,arg3,arg4); + p->_from_construct = true; + if(p->_name==NULL) { + p->register_object(new_name(p)); + } + return p->_name; + } +#endif + +}; + +/* Macro MBED_OBJECT_NAME_MAX + * The maximum size of object name (including terminating null byte) + * that will be recognised when using fopen to open a FileLike + * object, or when using the rpc function. + */ +#define MBED_OBJECT_NAME_MAX 32 + +/* Macro MBED_METHOD_NAME_MAX + * The maximum size of rpc method name (including terminating null + * byte) that will be recognised by the rpc function (in rpc.h). + */ +#define MBED_METHOD_NAME_MAX 32 + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/BusIn.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/BusIn.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,82 @@ +/* mbed Microcontroller Library - DigitalIn + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_BUSIN_H +#define MBED_BUSIN_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" +#include "DigitalIn.h" + +namespace mbed { + +/* Class: BusIn + * A digital input bus, used for reading the state of a collection of pins + */ +class BusIn : public Base { + +public: + + /* Group: Configuration Methods */ + + /* Constructor: BusIn + * Create an BusIn, connected to the specified pins + * + * Variables: + * p<n> - DigitalIn pin to connect to bus bit <n> (p5-p30, NC) + * + * Note: + * It is only required to specify as many pin variables as is required + * for the bus; the rest will default to NC (not connected) + */ + BusIn(PinName p0, PinName p1 = NC, PinName p2 = NC, PinName p3 = NC, + PinName p4 = NC, PinName p5 = NC, PinName p6 = NC, PinName p7 = NC, + PinName p8 = NC, PinName p9 = NC, PinName p10 = NC, PinName p11 = NC, + PinName p12 = NC, PinName p13 = NC, PinName p14 = NC, PinName p15 = NC, + const char *name = NULL); + + BusIn(PinName pins[16], const char *name = NULL); + + virtual ~BusIn(); + + /* Group: Access Methods */ + + /* Function: read + * Read the value of the input bus + * + * Variables: + * returns - An integer with each bit corresponding to the value read from the associated DigitalIn pin + */ + int read(); + +#ifdef MBED_OPERATORS + /* Group: Access Method Shorthand */ + + /* Function: operator int() + * A shorthand for <read> + */ + operator int(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + DigitalIn* _pin[16]; + +#ifdef MBED_RPC + static void construct(const char *arguments, char *res); +#endif + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/BusInOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/BusInOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,115 @@ +/* mbed Microcontroller Library - BusInOut + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_BUSINOUT_H +#define MBED_BUSINOUT_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" +#include "DigitalInOut.h" + +namespace mbed { + +/* Class: BusInOut + * A digital input output bus, used for setting the state of a collection of pins + */ +class BusInOut : public Base { + +public: + + /* Group: Configuration Methods */ + + /* Constructor: BusInOut + * Create an BusInOut, connected to the specified pins + * + * Variables: + * p<n> - DigitalInOut pin to connect to bus bit p<n> (p5-p30, NC) + * + * Note: + * It is only required to specify as many pin variables as is required + * for the bus; the rest will default to NC (not connected) + */ + BusInOut(PinName p0, PinName p1 = NC, PinName p2 = NC, PinName p3 = NC, + PinName p4 = NC, PinName p5 = NC, PinName p6 = NC, PinName p7 = NC, + PinName p8 = NC, PinName p9 = NC, PinName p10 = NC, PinName p11 = NC, + PinName p12 = NC, PinName p13 = NC, PinName p14 = NC, PinName p15 = NC, + const char *name = NULL); + + BusInOut(PinName pins[16], const char *name = NULL); + + virtual ~BusInOut(); + + /* Group: Access Methods */ + + /* Function: write + * Write the value to the output bus + * + * Variables: + * value - An integer specifying a bit to write for every corresponding DigitalInOut pin + */ + void write(int value); + + + /* Function: read + * Read the value currently output on the bus + * + * Variables: + * returns - An integer with each bit corresponding to associated DigitalInOut pin setting + */ + int read(); + + /* Function: output + * Set as an output + */ + void output(); + + /* Function: input + * Set as an input + */ + void input(); + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone + */ + void mode(PinMode pull); + +#ifdef MBED_OPERATORS + /* Group: Access Method Shorthand */ + + /* Function: operator= + * A shorthand for <write> + */ + BusInOut& operator= (int v); + BusInOut& operator= (BusInOut& rhs); + + /* Function: operator int() + * A shorthand for <read> + */ + operator int(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + DigitalInOut* _pin[16]; + +#ifdef MBED_RPC + static void construct(const char *arguments, char *res); +#endif + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/BusOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/BusOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,97 @@ +/* mbed Microcontroller Library - BusOut + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_BUSOUT_H +#define MBED_BUSOUT_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" +#include "DigitalOut.h" + +namespace mbed { + +/* Class: BusOut + * A digital output bus, used for setting the state of a collection of pins + */ +class BusOut : public Base { + +public: + + /* Group: Configuration Methods */ + + /* Constructor: BusOut + * Create an BusOut, connected to the specified pins + * + * Variables: + * p<n> - DigitalOut pin to connect to bus bit <n> (p5-p30, NC) + * + * Note: + * It is only required to specify as many pin variables as is required + * for the bus; the rest will default to NC (not connected) + */ + BusOut(PinName p0, PinName p1 = NC, PinName p2 = NC, PinName p3 = NC, + PinName p4 = NC, PinName p5 = NC, PinName p6 = NC, PinName p7 = NC, + PinName p8 = NC, PinName p9 = NC, PinName p10 = NC, PinName p11 = NC, + PinName p12 = NC, PinName p13 = NC, PinName p14 = NC, PinName p15 = NC, + const char *name = NULL); + + BusOut(PinName pins[16], const char *name = NULL); + + virtual ~BusOut(); + + /* Group: Access Methods */ + + /* Function: write + * Write the value to the output bus + * + * Variables: + * value - An integer specifying a bit to write for every corresponding DigitalOut pin + */ + void write(int value); + + + /* Function: read + * Read the value currently output on the bus + * + * Variables: + * returns - An integer with each bit corresponding to associated DigitalOut pin setting + */ + int read(); + +#ifdef MBED_OPERATORS + /* Group: Access Method Shorthand */ + + /* Function: operator= + * A shorthand for <write> + */ + BusOut& operator= (int v); + BusOut& operator= (BusOut& rhs); + + /* Function: operator int() + * A shorthand for <read> + */ + operator int(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + DigitalOut* _pin[16]; + +#ifdef MBED_RPC + static void construct(const char *arguments, char *res); +#endif + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/CAN.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/CAN.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,252 @@ +/* mbed Microcontroller Library - can + * Copyright (c) 2009-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_CAN_H +#define MBED_CAN_H + +#include "device.h" + +#if DEVICE_CAN + +#include "Base.h" +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" + +#include "can_helper.h" +#include "FunctionPointer.h" + +#include <string.h> + +namespace mbed { + +/* Class: CANMessage + * + */ +class CANMessage : public CAN_Message { + +public: + + /* Constructor: CANMessage + * Creates empty CAN message. + */ + CANMessage() { + len = 8; + type = CANData; + format = CANStandard; + id = 0; + memset(data, 0, 8); + } + + /* Constructor: CANMessage + * Creates CAN message with specific content. + */ + CANMessage(int _id, const char *_data, char _len = 8, CANType _type = CANData, CANFormat _format = CANStandard) { + len = _len & 0xF; + type = _type; + format = _format; + id = _id; + memcpy(data, _data, _len); + } + + /* Constructor: CANMessage + * Creates CAN remote message. + */ + CANMessage(int _id, CANFormat _format = CANStandard) { + len = 0; + type = CANRemote; + format = _format; + id = _id; + memset(data, 0, 8); + } +#if 0 // Inhereted from CAN_Message, for documentation only + + /* Variable: id + * The message id. + * + * If format is CANStandard it must be an 11 bit long id + * If format is CANExtended it must be an 29 bit long id + */ + unsigned int id; + + /* Variable: data + * Space for 8 byte payload. + * + * If type is CANData data can store up to 8 byte data. + */ + unsigned char data[8]; + + /* Variable: len + * Length of data in bytes. + * + * If type is CANData data can store up to 8 byte data. + */ + unsigned char len; + + /* Variable: format + * Defines if the message has standard or extended format. + * + * Defines the type of message id: + * Default is CANStandard which implies 11 bit id. + * CANExtended means 29 bit message id. + */ + CANFormat format; + + /* Variable: type + * Defines the type of a message. + * + * The message type can rather be CANData for a message with data (default). + * Or CANRemote for a request of a specific CAN message. + */ + CANType type; // 0 - DATA FRAME, 1 - REMOTE FRAME +#endif +}; + +/* Class: CAN + * A can bus client, used for communicating with can devices + */ +class CAN : public Base { + +public: + + /* Constructor: CAN + * Creates an CAN interface connected to specific pins. + * + * Example: + * > #include "mbed.h" + * > + * > Ticker ticker; + * > DigitalOut led1(LED1); + * > DigitalOut led2(LED2); + * > CAN can1(p9, p10); + * > CAN can2(p30, p29); + * > + * > char counter = 0; + * > + * > void send() { + * > if(can1.write(CANMessage(1337, &counter, 1))) { + * > printf("Message sent: %d\n", counter); + * > counter++; + * > } + * > led1 = !led1; + * > } + * > + * > int main() { + * > ticker.attach(&send, 1); + * > CANMessage msg; + * > while(1) { + * > if(can2.read(msg)) { + * > printf("Message received: %d\n\n", msg.data[0]); + * > led2 = !led2; + * > } + * > wait(0.2); + * > } + * > } + * + * Variables: + * rd - read from transmitter + * td - transmit to transmitter + */ + CAN(PinName rd, PinName td); + virtual ~CAN(); + + /* Function: frequency + * Set the frequency of the CAN interface + * + * Variables: + * hz - The bus frequency in hertz + * returns - 1 if successful, 0 otherwise + */ + int frequency(int hz); + + /* Function: write + * Write a CANMessage to the bus. + * + * Variables: + * msg - The CANMessage to write. + * + * Returns: + * 0 - If write failed. + * 1 - If write was successful. + */ + int write(CANMessage msg); + + /* Function: read + * Read a CANMessage from the bus. + * + * Variables: + * msg - A CANMessage to read to. + * + * Returns: + * 0 - If no message arrived. + * 1 - If message arrived. + */ + int read(CANMessage &msg); + + /* Function: reset + * Reset CAN interface. + * + * To use after error overflow. + */ + void reset(); + + /* Function: monitor + * Puts or removes the CAN interface into silent monitoring mode + * + * Variables: + * silent - boolean indicating whether to go into silent mode or not + */ + void monitor(bool silent); + + /* Function: rderror + * Returns number of read errors to detect read overflow errors. + */ + unsigned char rderror(); + + /* Function: tderror + * Returns number of write errors to detect write overflow errors. + */ + unsigned char tderror(); + + /* Function: attach + * Attach a function to call whenever a CAN frame received interrupt is + * generated. + * + * Variables: + * fptr - A pointer to a void function, or 0 to set as none + */ + void attach(void (*fptr)(void)); + + /* Function attach + * Attach a member function to call whenever a CAN frame received interrupt + * is generated. + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + */ + template<typename T> + void attach(T* tptr, void (T::*mptr)(void)) { + if((mptr != NULL) && (tptr != NULL)) { + _rxirq.attach(tptr, mptr); + setup_interrupt(); + } else { + remove_interrupt(); + } + } + +private: + + CANName _id; + FunctionPointer _rxirq; + + void setup_interrupt(void); + void remove_interrupt(void); +}; + +} // namespace mbed + +#endif // MBED_CAN_H + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/DigitalIn.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/DigitalIn.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,102 @@ +/* mbed Microcontroller Library - DigitalIn + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_DIGITALIN_H +#define MBED_DIGITALIN_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: DigitalIn + * A digital input, used for reading the state of a pin + * + * Example: + * > // Flash an LED while a DigitalIn is true + * > + * > #include "mbed.h" + * > + * > DigitalIn enable(p5); + * > DigitalOut led(LED1); + * > + * > int main() { + * > while(1) { + * > if(enable) { + * > led = !led; + * > } + * > wait(0.25); + * > } + * > } + */ +class DigitalIn : public Base { + +public: + + /* Constructor: DigitalIn + * Create a DigitalIn connected to the specified pin + * + * Variables: + * pin - DigitalIn pin to connect to + * name - (optional) A string to identify the object + */ + DigitalIn(PinName pin, const char *name = NULL); + + /* Function: read + * Read the input, represented as 0 or 1 (int) + * + * Variables: + * returns - An integer representing the state of the input pin, + * 0 for logical 0 and 1 for logical 1 + */ + int read() { +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + return ((_gpio->FIOPIN & _mask) ? 1 : 0); +#elif defined(TARGET_LPC11U24) + return ((LPC_GPIO->PIN[_index] & _mask) ? 1 : 0); +#endif + } + + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone, OpenDrain + */ + void mode(PinMode pull); + +#ifdef MBED_OPERATORS + /* Function: operator int() + * An operator shorthand for <read()> + */ + operator int() { + return read(); + } + +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + PinName _pin; +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#elif defined(TARGET_LPC11U24) + int _index; +#endif + uint32_t _mask; + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/DigitalInOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/DigitalInOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,134 @@ +/* mbed Microcontroller Library - DigitalInOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_DIGITALINOUT_H +#define MBED_DIGITALINOUT_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: DigitalInOut + * A digital input/output, used for setting or reading a bi-directional pin + */ +class DigitalInOut : public Base { + +public: + + /* Constructor: DigitalInOut + * Create a DigitalInOut connected to the specified pin + * + * Variables: + * pin - DigitalInOut pin to connect to + */ + DigitalInOut(PinName pin, const char* name = NULL); + + /* Function: write + * Set the output, specified as 0 or 1 (int) + * + * Variables: + * value - An integer specifying the pin output value, + * 0 for logical 0 and 1 (or any other non-zero value) for logical 1 + */ + void write(int value) { +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + + if(value) { + _gpio->FIOSET = _mask; + } else { + _gpio->FIOCLR = _mask; + } + +#elif defined(TARGET_LPC11U24) + + if(value) { + LPC_GPIO->SET[_index] = _mask; + } else { + LPC_GPIO->CLR[_index] = _mask; + } +#endif + } + + /* Function: read + * Return the output setting, represented as 0 or 1 (int) + * + * Variables: + * returns - An integer representing the output setting of the pin if it is an output, + * or read the input if set as an input + */ + int read() { +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + + return ((_gpio->FIOPIN & _mask) ? 1 : 0); +#elif defined(TARGET_LPC11U24) + return ((LPC_GPIO->PIN[_index] & _mask) ? 1 : 0); +#endif + } + + + /* Function: output + * Set as an output + */ + void output(); + + /* Function: input + * Set as an input + */ + void input(); + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone, OpenDrain + */ + void mode(PinMode pull); + +#ifdef MBED_OPERATORS + /* Function: operator= + * A shorthand for <write> + */ + DigitalInOut& operator= (int value) { + write(value); + return *this; + } + + DigitalInOut& operator= (DigitalInOut& rhs) { + write(rhs.read()); + return *this; + } + + /* Function: operator int() + * A shorthand for <read> + */ + operator int() { + return read(); + } +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + PinName _pin; + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#elif defined(TARGET_LPC11U24) + int _index; +#endif + + uint32_t _mask; + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/DigitalOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/DigitalOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,134 @@ +/* mbed Microcontroller Library - DigitalOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_DIGITALOUT_H +#define MBED_DIGITALOUT_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: DigitalOut + * A digital output, used for setting the state of a pin + * + * Example: + * > // Toggle a LED + * > #include "mbed.h" + * > + * > DigitalOut led(LED1); + * > + * > int main() { + * > while(1) { + * > led = !led; + * > wait(0.2); + * > } + * > } + */ +class DigitalOut : public Base { + +public: + + /* Constructor: DigitalOut + * Create a DigitalOut connected to the specified pin + * + * Variables: + * pin - DigitalOut pin to connect to + */ + DigitalOut(PinName pin, const char* name = NULL); + + /* Function: write + * Set the output, specified as 0 or 1 (int) + * + * Variables: + * value - An integer specifying the pin output value, + * 0 for logical 0 and 1 (or any other non-zero value) for logical 1 + */ + void write(int value) { + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + + if(value) { + _gpio->FIOSET = _mask; + } else { + _gpio->FIOCLR = _mask; + } + +#elif defined(TARGET_LPC11U24) + + if(value) { + LPC_GPIO->SET[_index] = _mask; + } else { + LPC_GPIO->CLR[_index] = _mask; + } +#endif + + } + + /* Function: read + * Return the output setting, represented as 0 or 1 (int) + * + * Variables: + * returns - An integer representing the output setting of the pin, + * 0 for logical 0 and 1 for logical 1 + */ + int read() { +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + return ((_gpio->FIOPIN & _mask) ? 1 : 0); +#elif defined(TARGET_LPC11U24) + return ((LPC_GPIO->PIN[_index] & _mask) ? 1 : 0); +#endif + + } + + +#ifdef MBED_OPERATORS + /* Function: operator= + * A shorthand for <write> + */ + DigitalOut& operator= (int value) { + write(value); + return *this; + } + + DigitalOut& operator= (DigitalOut& rhs) { + write(rhs.read()); + return *this; + } + + + /* Function: operator int() + * A shorthand for <read> + */ + operator int() { + return read(); + } + +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + PinName _pin; + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#elif defined(TARGET_LPC11U24) + int _index; +#endif + + uint32_t _mask; + + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/DirHandle.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/DirHandle.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,96 @@ +/* mbed Microcontroller Library - DirHandler + * Copyright (c) 2008-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_DIRHANDLE_H +#define MBED_DIRHANDLE_H + +#ifdef __ARMCC_VERSION +# define NAME_MAX 255 +typedef int mode_t; +#else +# include <sys/syslimits.h> +#endif +#include "FileHandle.h" + +struct dirent { + char d_name[NAME_MAX+1]; +}; + +namespace mbed { + +/* Class DirHandle + * Represents a directory stream. Objects of this type are returned + * by a FileSystemLike's opendir method. Implementations must define + * at least closedir, readdir and rewinddir. + * + * If a FileSystemLike class defines the opendir method, then the + * directories of an object of that type can be accessed by + * DIR *d = opendir("/example/directory") (or opendir("/example") + * to open the root of the filesystem), and then using readdir(d) etc. + * + * The root directory is considered to contain all FileLike and + * FileSystemLike objects, so the DIR* returned by opendir("/") will + * reflect this. + */ +class DirHandle { + + public: + /* Function closedir + * Closes the directory. + * + * Variables + * returns - 0 on success, or -1 on error. + */ + virtual int closedir()=0; + + /* Function readdir + * Return the directory entry at the current position, and + * advances the position to the next entry. + * + * Returns + * A pointer to a dirent structure representing the + * directory entry at the current position, or NULL on reaching + * end of directory or error. + */ + virtual struct dirent *readdir()=0; + + /* Function rewinddir + * Resets the position to the beginning of the directory. + */ + virtual void rewinddir()=0; + + /* Function telldir + * Returns the current position of the DirHandle. + * + * Returns + * The current position, or -1 on error. + */ + virtual off_t telldir() { return -1; } + + /* Function seekdir + * Sets the position of the DirHandle. + * + * Variables + * location - The location to seek to. Must be a value returned + * by telldir. + */ + virtual void seekdir(off_t location) { } + +}; + +} // namespace mbed + +typedef mbed::DirHandle DIR; + +extern "C" { + DIR *opendir(const char*); + struct dirent *readdir(DIR *); + int closedir(DIR*); + void rewinddir(DIR*); + long telldir(DIR*); + void seekdir(DIR*, long); + int mkdir(const char *name, mode_t n); +}; + +#endif /* MBED_DIRHANDLE_H */
diff -r 000000000000 -r 80df663dd15e mbed/Ethernet.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Ethernet.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,173 @@ +/* mbed Microcontroller Library - Ethernet + * Copyright (c) 2009-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_ETHERNET_H +#define MBED_ETHERNET_H + +#include "device.h" + +#if DEVICE_ETHERNET + +#include "Base.h" + +namespace mbed { + +/* Class: Ethernet + * An ethernet interface, to use with the ethernet pins. + * + * Example: + * > // Read destination and source from every ethernet packet + * > + * > #include "mbed.h" + * > + * > Ethernet eth; + * > + * > int main() { + * > char buf[0x600]; + * > + * > while(1) { + * > int size = eth.receive(); + * > if(size > 0) { + * > eth.read(buf, size); + * > printf("Destination: %02X:%02X:%02X:%02X:%02X:%02X\n", + * > buf[0], buf[1], buf[2], buf[3], buf[4], buf[5]); + * > printf("Source: %02X:%02X:%02X:%02X:%02X:%02X\n", + * > buf[6], buf[7], buf[8], buf[9], buf[10], buf[11]); + * > } + * > + * > wait(1); + * > } + * > } + * + */ +class Ethernet : public Base { + +public: + + /* Constructor: Ethernet + * Initialise the ethernet interface. + */ + Ethernet(); + + /* Destructor: Ethernet + * Powers the hardware down. + */ + virtual ~Ethernet(); + + enum Mode { + AutoNegotiate + , HalfDuplex10 + , FullDuplex10 + , HalfDuplex100 + , FullDuplex100 + }; + + /* Function: write + * Writes into an outgoing ethernet packet. + * + * It will append size bytes of data to the previously written bytes. + * + * Variables: + * data - An array to write. + * size - The size of data. + * + * Returns: + * The number of written bytes. + */ + int write(const char *data, int size); + + /* Function: send + * Send an outgoing ethernet packet. + * + * After filling in the data in an ethernet packet it must be send. + * Send will provide a new packet to write to. + * + * Returns: + * 0 - If the sending was failed. + * 1 - If the package is successfully sent. + */ + int send(); + + /* Function: receive + * Recevies an arrived ethernet packet. + * + * Receiving an ethernet packet will drop the last received ethernet packet + * and make a new ethernet packet ready to read. + * If no ethernet packet is arrived it will return 0. + * + * Returns: + * 0 - If no ethernet packet is arrived. + * The size of the arrived packet. + */ + int receive(); + + /* Function: read + * Read from an recevied ethernet packet. + * + * After receive returnd a number bigger than 0it is + * possible to read bytes from this packet. + * Read will write up to size bytes into data. + * + * It is possible to use read multible times. + * Each time read will start reading after the last read byte before. + * + * Returns: + * The number of byte read. + */ + int read(char *data, int size); + + /* Function: address + * Gives the ethernet address of the mbed. + * + * Variables: + * mac - Must be a pointer to a 6 byte char array to copy the ethernet address in. + */ + void address(char *mac); + + /* Function: link + * Returns if an ethernet link is pressent or not. It takes a wile after Ethernet initializion to show up. + * + * Returns: + * 0 - If no ethernet link is pressent. + * 1 - If an ethernet link is pressent. + * + * Example: + * > // Using the Ethernet link function + * > #include "mbed.h" + * > + * > Ethernet eth; + * > + * > int main() { + * > wait(1); // Needed after startup. + * > if(eth.link()) { + * > printf("online\n"); + * > } else { + * > printf("offline\n"); + * > } + * > } + * + */ + int link(); + + /* Function: set_link + * Sets the speed and duplex parameters of an ethernet link + * + * Variables: + * mode - the speed and duplex mode to set the link to: + * + * > AutoNegotiate Auto negotiate speed and duplex + * > HalfDuplex10 10 Mbit, half duplex + * > FullDuplex10 10 Mbit, full duplex + * > HalfDuplex100 100 Mbit, half duplex + * > FullDuplex100 100 Mbit, full duplex + */ + void set_link(Mode mode); + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/FileHandle.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/FileHandle.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,114 @@ +/* mbed Microcontroller Library - FileHandler + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_FILEHANDLE_H +#define MBED_FILEHANDLE_H + +typedef int FILEHANDLE; + +#include <stdio.h> +#ifdef __ARMCC_VERSION +typedef int ssize_t; +typedef long off_t; +#else +#include <sys/types.h> +#endif + +namespace mbed { + +/* Class FileHandle + * An OO equivalent of the internal FILEHANDLE variable + * and associated _sys_* functions + * + * FileHandle is an abstract class, needing at least sys_write and + * sys_read to be implmented for a simple interactive device + * + * No one ever directly tals to/instanciates a FileHandle - it gets + * created by FileSystem, and wrapped up by stdio + */ +class FileHandle { + +public: + + /* Function write + * Write the contents of a buffer to the file + * + * Parameters + * buffer - the buffer to write from + * length - the number of characters to write + * + * Returns + * The number of characters written (possibly 0) on success, -1 on error. + */ + virtual ssize_t write(const void* buffer, size_t length) = 0; + + /* Function close + * Close the file + * + * Returns + * Zero on success, -1 on error. + */ + virtual int close() = 0; + + /* Function read + * Reads the contents of the file into a buffer + * + * Parameters + * buffer - the buffer to read in to + * length - the number of characters to read + * + * Returns + * The number of characters read (zero at end of file) on success, -1 on error. + */ + virtual ssize_t read(void* buffer, size_t length) = 0; + + /* Function isatty + * Check if the handle is for a interactive terminal device + * + * If so, line buffered behaviour is used by default + * + * Returns + * 1 if it is a terminal, 0 otherwise + */ + virtual int isatty() = 0 ; + + /* Function lseek + * Move the file position to a given offset from a given location. + * + * Parameters + * offset - The offset from whence to move to + * whence - SEEK_SET for the start of the file, SEEK_CUR for the + * current file position, or SEEK_END for the end of the file. + * + * Returns + * New file position on success, -1 on failure or unsupported + */ + virtual off_t lseek(off_t offset, int whence) = 0; + + /* Function fsync + * Flush any buffers associated with the FileHandle, ensuring it + * is up to date on disk + * + * Returns + * 0 on success or un-needed, -1 on error + */ + virtual int fsync() = 0; + + virtual off_t flen() { + /* remember our current position */ + off_t pos = lseek(0, SEEK_CUR); + if(pos == -1) return -1; + /* seek to the end to get the file length */ + off_t res = lseek(0, SEEK_END); + /* return to our old position */ + lseek(pos, SEEK_SET); + return res; + } + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/FileLike.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/FileLike.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,33 @@ +/* mbed Microcontroller Library - FileLike + * Copyright (c) 2008-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_FILELIKE_H +#define MBED_FILELIKE_H + +#include "Base.h" +#include "FileHandle.h" + +namespace mbed { + +/* Class FileLike + * A file-like object is one that can be opened with fopen by + * fopen("/name", mode). It is intersection of the classes Base and + * FileHandle. + */ +class FileLike : public Base, public FileHandle { + + public: + /* Constructor FileLike + * + * Variables + * name - The name to use to open the file. + */ + FileLike(const char *name) : Base(name) { } + virtual ~FileLike(); + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/FileSystemLike.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/FileSystemLike.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,100 @@ +/* mbed Microcontroller Library - FileSystemLike + * Copyright (c) 2008-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_FILESYSTEMLIKE_H +#define MBED_FILESYSTEMLIKE_H + +#ifdef __ARMCC_VERSION +# define O_RDONLY 0 +# define O_WRONLY 1 +# define O_RDWR 2 +# define O_CREAT 0x0200 +# define O_TRUNC 0x0400 +# define O_APPEND 0x0008 +typedef int mode_t; +#else +# include <sys/fcntl.h> +#endif +#include "Base.h" +#include "FileHandle.h" +#include "DirHandle.h" + +namespace mbed { + +/* Class FileSystemLike + * A filesystem-like object is one that can be used to open files + * though it by fopen("/name/filename", mode) + * + * Implementations must define at least open (the default definitions + * of the rest of the functions just return error values). + */ +class FileSystemLike : public Base { + + public: + + /* Constructor FileSystemLike + * + * Variables + * name - The name to use for the filesystem. + */ + FileSystemLike(const char *name) : Base(name) {} + + /* Function open + * + * Variables + * filename - The name of the file to open. + * flags - One of O_RDONLY, O_WRONLY, or O_RDWR, OR'd with + * zero or more of O_CREAT, O_TRUNC, or O_APPEND. + * returns - A pointer to a FileHandle object representing the + * file on success, or NULL on failure. + */ + virtual FileHandle *open(const char *filename, int flags) = 0; + + /* Function remove + * Remove a file from the filesystem. + * + * Variables + * filename - the name of the file to remove. + * returns - 0 on success, -1 on failure. + */ + virtual int remove(const char *filename) { return -1; }; + + /* Function rename + * Rename a file in the filesystem. + * + * Variables + * oldname - the name of the file to rename. + * newname - the name to rename it to. + * returns - 0 on success, -1 on failure. + */ + virtual int rename(const char *oldname, const char *newname) { return -1; }; + + /* Function opendir + * Opens a directory in the filesystem and returns a DirHandle + * representing the directory stream. + * + * Variables + * name - The name of the directory to open. + * returns - A DirHandle representing the directory stream, or + * NULL on failure. + */ + virtual DirHandle *opendir(const char *name) { return NULL; }; + + /* Function mkdir + * Creates a directory in the filesystem. + * + * Variables + * name - The name of the directory to create. + * mode - The permissions to create the directory with. + * returns - 0 on success, -1 on failure. + */ + virtual int mkdir(const char *name, mode_t mode) { return -1; } + + // TODO other filesystem functions (mkdir, rm, rn, ls etc) + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/FunctionPointer.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/FunctionPointer.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,86 @@ +/* mbed Microcontroller Library - FunctionPointer + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_FUNCTIONPOINTER_H +#define MBED_FUNCTIONPOINTER_H + +#include <string.h> + +namespace mbed { + +/* Class FunctionPointer + * A class for storing and calling a pointer to a static or member void function + */ +class FunctionPointer { + +public: + + /* Constructor FunctionPointer + * Create a FunctionPointer, attaching a static function + * + * Variables + * function - The void static function to attach (default is none) + */ + FunctionPointer(void (*function)(void) = 0); + + /* Constructor FunctionPointer + * Create a FunctionPointer, attaching a member function + * + * Variables + * object - The object pointer to invoke the member function on (i.e. the this pointer) + * function - The address of the void member function to attach + */ + template<typename T> + FunctionPointer(T *object, void (T::*member)(void)) { + attach(object, member); + } + + /* Function attach + * Attach a static function + * + * Variables + * function - The void static function to attach (default is none) + */ + void attach(void (*function)(void) = 0); + + /* Function attach + * Attach a member function + * + * Variables + * object - The object pointer to invoke the member function on (i.e. the this pointer) + * function - The address of the void member function to attach + */ + template<typename T> + void attach(T *object, void (T::*member)(void)) { + _object = static_cast<void*>(object); + memcpy(_member, (char*)&member, sizeof(member)); + _membercaller = &FunctionPointer::membercaller<T>; + _function = 0; + } + + /* Function call + * Call the attached static or member function + */ + void call(); + +private: + + template<typename T> + static void membercaller(void *object, char *member) { + T* o = static_cast<T*>(object); + void (T::*m)(void); + memcpy((char*)&m, member, sizeof(m)); + (o->*m)(); + } + + void (*_function)(void); // static function pointer - 0 if none attached + void *_object; // object this pointer - 0 if none attached + char _member[16]; // raw member function pointer storage - converted back by registered _membercaller + void (*_membercaller)(void*, char*); // registered membercaller function to convert back and call _member on _object + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/I2C.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/I2C.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,142 @@ +/* mbed Microcontroller Library - I2C + * Copyright (c) 2007-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_I2C_H +#define MBED_I2C_H + +#include "device.h" + +#if DEVICE_I2C + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: I2C + * An I2C Master, used for communicating with I2C slave devices + * + * Example: + * > // Read from I2C slave at address 0x62 + * > + * > #include "mbed.h" + * > + * > I2C i2c(p28, p27); + * > + * > int main() { + * > int address = 0x62; + * > char data[2]; + * > i2c.read(address, data, 2); + * > } + */ +class I2C : public Base { + +public: + + enum RxStatus { + NoData + , MasterGeneralCall + , MasterWrite + , MasterRead + }; + + enum Acknowledge { + NoACK = 0 + , ACK = 1 + }; + + /* Constructor: I2C + * Create an I2C Master interface, connected to the specified pins + * + * Variables: + * sda - I2C data line pin + * scl - I2C clock line pin + */ + I2C(PinName sda, PinName scl, const char *name = NULL); + + /* Function: frequency + * Set the frequency of the I2C interface + * + * Variables: + * hz - The bus frequency in hertz + */ + void frequency(int hz); + + /* Function: read + * Read from an I2C slave + * + * Performs a complete read transaction. The bottom bit of + * the address is forced to 1 to indicate a read. + * + * Variables: + * address - 8-bit I2C slave address [ addr | 1 ] + * data - Pointer to the byte-array to read data in to + * length - Number of bytes to read + * repeated - Repeated start, true - don't send stop at end + * returns - 0 on success (ack), or non-0 on failure (nack) + */ + int read(int address, char *data, int length, bool repeated = false); + + /* Function: read + * Read a single byte from the I2C bus + * + * Variables: + * ack - indicates if the byte is to be acknowledged (1 = acknowledge) + * returns - the byte read + */ + int read(int ack); + + /* Function: write + * Write to an I2C slave + * + * Performs a complete write transaction. The bottom bit of + * the address is forced to 0 to indicate a write. + * + * Variables: + * address - 8-bit I2C slave address [ addr | 0 ] + * data - Pointer to the byte-array data to send + * length - Number of bytes to send + * repeated - Repeated start, true - do not send stop at end + * returns - 0 on success (ack), or non-0 on failure (nack) + */ + int write(int address, const char *data, int length, bool repeated = false); + + /* Function: write + * Write single byte out on the I2C bus + * + * Variables: + * data - data to write out on bus + * returns - a '1' if an ACK was received, a '0' otherwise + */ + int write(int data); + + /* Function: start + * Creates a start condition on the I2C bus + */ + + void start(void); + + /* Function: stop + * Creates a stop condition on the I2C bus + */ + void stop(void); + +protected: + + void aquire(); + + I2CName _i2c; + static I2C *_owner; + int _hz; + +}; + +} // namespace mbed + +#endif + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/I2CSlave.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/I2CSlave.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,155 @@ +/* mbed Microcontroller Library - I2CSlave + * Copyright (c) 2007-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_I2C_SLAVE_H +#define MBED_I2C_SLAVE_H + +#include "device.h" + +#if DEVICE_I2CSLAVE + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: I2CSlave + * An I2C Slave, used for communicating with an I2C Master device + * + * Example: + * > // Simple I2C responder + * > #include <mbed.h> + * > + * > I2CSlave slave(p9, p10); + * > + * > int main() { + * > char buf[10]; + * > char msg[] = "Slave!"; + * > + * > slave.address(0xA0); + * > while (1) { + * > int i = slave.receive(); + * > switch (i) { + * > case I2CSlave::ReadAddressed: + * > slave.write(msg, strlen(msg) + 1); // Includes null char + * > break; + * > case I2CSlave::WriteGeneral: + * > slave.read(buf, 10); + * > printf("Read G: %s\n", buf); + * > break; + * > case I2CSlave::WriteAddressed: + * > slave.read(buf, 10); + * > printf("Read A: %s\n", buf); + * > break; + * > } + * > for(int i = 0; i < 10; i++) buf[i] = 0; // Clear buffer + * > } + * > } + * > + */ +class I2CSlave : public Base { + +public: + + enum RxStatus { + NoData = 0 + , ReadAddressed = 1 + , WriteGeneral = 2 + , WriteAddressed = 3 + }; + + /* Constructor: I2CSlave + * Create an I2C Slave interface, connected to the specified pins. + * + * Variables: + * sda - I2C data line pin + * scl - I2C clock line pin + */ + I2CSlave(PinName sda, PinName scl, const char *name = NULL); + + /* Function: frequency + * Set the frequency of the I2C interface + * + * Variables: + * hz - The bus frequency in hertz + */ + void frequency(int hz); + + /* Function: receive + * Checks to see if this I2C Slave has been addressed. + * + * Variables: + * returns - a status indicating if the device has been addressed, and how + * > NoData - the slave has not been addressed + * > ReadAddressed - the master has requested a read from this slave + * > WriteAddressed - the master is writing to this slave + * > WriteGeneral - the master is writing to all slave + */ + int receive(void); + + /* Function: read + * Read from an I2C master. + * + * Variables: + * data - pointer to the byte array to read data in to + * length - maximum number of bytes to read + * returns - 0 on success, non-0 otherwise + */ + int read(char *data, int length); + + /* Function: read + * Read a single byte from an I2C master. + * + * Variables: + * returns - the byte read + */ + int read(void); + + /* Function: write + * Write to an I2C master. + * + * Variables: + * data - pointer to the byte array to be transmitted + * length - the number of bytes to transmite + * returns - a 0 on success, non-0 otherwise + */ + int write(const char *data, int length); + + /* Function: write + * Write a single byte to an I2C master. + * + * Variables + * data - the byte to write + * returns - a '1' if an ACK was received, a '0' otherwise + */ + int write(int data); + + /* Function: address + * Sets the I2C slave address. + * + * Variables + * address - the address to set for the slave (ignoring the least + * signifcant bit). If set to 0, the slave will only respond to the + * general call address. + */ + void address(int address); + + /* Function: stop + * Reset the I2C slave back into the known ready receiving state. + */ + void stop(void); + +protected: + + I2CName _i2c; +}; + +} // namespace mbed + +#endif + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/InterruptIn.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/InterruptIn.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,149 @@ +/* mbed Microcontroller Library - InterruptIn + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_INTERRUPTIN_H +#define MBED_INTERRUPTIN_H + +#include "device.h" + +#if DEVICE_INTERRUPTIN + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" +#include "FunctionPointer.h" + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) +#define CHANNEL_NUM 48 +#elif defined(TARGET_LPC11U24) +#define CHANNEL_NUM 8 +#endif + +namespace mbed { + +/* Class: InterruptIn + * A digital interrupt input, used to call a function on a rising or falling edge + * + * Example: + * > // Flash an LED while waiting for events + * > + * > #include "mbed.h" + * > + * > InterruptIn event(p16); + * > DigitalOut led(LED1); + * > + * > void trigger() { + * > printf("triggered!\n"); + * > } + * > + * > int main() { + * > event.rise(&trigger); + * > while(1) { + * > led = !led; + * > wait(0.25); + * > } + * > } + */ +class InterruptIn : public Base { + +public: + + /* Constructor: InterruptIn + * Create an InterruptIn connected to the specified pin + * + * Variables: + * pin - InterruptIn pin to connect to + * name - (optional) A string to identify the object + */ + InterruptIn(PinName pin, const char *name = NULL); +#if defined(TARGET_LPC11U24) + virtual ~InterruptIn(); +#endif + + int read(); +#ifdef MBED_OPERATORS + operator int(); + +#endif + + /* Function: rise + * Attach a function to call when a rising edge occurs on the input + * + * Variables: + * fptr - A pointer to a void function, or 0 to set as none + */ + void rise(void (*fptr)(void)); + + /* Function: rise + * Attach a member function to call when a rising edge occurs on the input + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + */ + template<typename T> + void rise(T* tptr, void (T::*mptr)(void)) { + _rise.attach(tptr, mptr); + setup_interrupt(1, 1); + } + + /* Function: fall + * Attach a function to call when a falling edge occurs on the input + * + * Variables: + * fptr - A pointer to a void function, or 0 to set as none + */ + void fall(void (*fptr)(void)); + + /* Function: fall + * Attach a member function to call when a falling edge occurs on the input + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + */ + template<typename T> + void fall(T* tptr, void (T::*mptr)(void)) { + _fall.attach(tptr, mptr); + setup_interrupt(0, 1); + } + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone + */ + void mode(PinMode pull); + + static InterruptIn *_irq_objects[CHANNEL_NUM]; + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + static void _irq(); +#elif defined(TARGET_LPC11U24) + static void handle_interrupt_in(unsigned int channel); + static void _irq0(); static void _irq1(); + static void _irq2(); static void _irq3(); + static void _irq4(); static void _irq5(); + static void _irq6(); static void _irq7(); +#endif + +protected: + PinName _pin; +#if defined(TARGET_LPC11U24) + Channel _channel; +#endif + FunctionPointer _rise; + FunctionPointer _fall; + + void setup_interrupt(int rising, int enable); + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/LPC1768.sct --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/ARM/LPC1768.sct Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,22 @@ + +LR_IROM1 0x00000000 0x80000 { ; load region size_region + ER_IROM1 0x00000000 0x80000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + ; 8_byte_aligned(49 vect * 4 bytes) = 8_byte_aligned(0xC4) = 0xC8 + ; 32KB - 0xC8 = 0x7F38 + RW_IRAM1 0x100000C8 0x7F38 { + .ANY (+RW +ZI) + } + RW_IRAM2 0x2007C000 0x4000 { ; RW data, ETH RAM + .ANY (AHBSRAM0) + } + RW_IRAM3 0x20080000 0x4000 { ; RW data, ETH RAM + .ANY (AHBSRAM1) + } + RW_IRAM4 0x40038000 0x0800 { ; RW data, CAN RAM + .ANY (CANRAM) + } +}
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/capi.ar Binary file mbed/LPC1768/ARM/capi.ar has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/cmsis_nvic.o Binary file mbed/LPC1768/ARM/cmsis_nvic.o has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/core_cm3.o Binary file mbed/LPC1768/ARM/core_cm3.o has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/mbed.ar Binary file mbed/LPC1768/ARM/mbed.ar has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/startup_LPC17xx.o Binary file mbed/LPC1768/ARM/startup_LPC17xx.o has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/sys.o Binary file mbed/LPC1768/ARM/sys.o has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/ARM/system_LPC17xx.o Binary file mbed/LPC1768/ARM/system_LPC17xx.o has changed
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/LPC17xx.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/LPC17xx.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,1035 @@ +/**************************************************************************//** + * @file LPC17xx.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File for + * NXP LPC17xx Device Series + * @version: V1.09 + * @date: 17. March 2010 + + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + + +#ifndef __LPC17xx_H__ +#define __LPC17xx_H__ + +/* + * ========================================================================== + * ---------- Interrupt Number Definition ----------------------------------- + * ========================================================================== + */ + +typedef enum IRQn +{ +/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ + +/****** LPC17xx Specific Interrupt Numbers *******************************************************/ + WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */ + TIMER0_IRQn = 1, /*!< Timer0 Interrupt */ + TIMER1_IRQn = 2, /*!< Timer1 Interrupt */ + TIMER2_IRQn = 3, /*!< Timer2 Interrupt */ + TIMER3_IRQn = 4, /*!< Timer3 Interrupt */ + UART0_IRQn = 5, /*!< UART0 Interrupt */ + UART1_IRQn = 6, /*!< UART1 Interrupt */ + UART2_IRQn = 7, /*!< UART2 Interrupt */ + UART3_IRQn = 8, /*!< UART3 Interrupt */ + PWM1_IRQn = 9, /*!< PWM1 Interrupt */ + I2C0_IRQn = 10, /*!< I2C0 Interrupt */ + I2C1_IRQn = 11, /*!< I2C1 Interrupt */ + I2C2_IRQn = 12, /*!< I2C2 Interrupt */ + SPI_IRQn = 13, /*!< SPI Interrupt */ + SSP0_IRQn = 14, /*!< SSP0 Interrupt */ + SSP1_IRQn = 15, /*!< SSP1 Interrupt */ + PLL0_IRQn = 16, /*!< PLL0 Lock (Main PLL) Interrupt */ + RTC_IRQn = 17, /*!< Real Time Clock Interrupt */ + EINT0_IRQn = 18, /*!< External Interrupt 0 Interrupt */ + EINT1_IRQn = 19, /*!< External Interrupt 1 Interrupt */ + EINT2_IRQn = 20, /*!< External Interrupt 2 Interrupt */ + EINT3_IRQn = 21, /*!< External Interrupt 3 Interrupt */ + ADC_IRQn = 22, /*!< A/D Converter Interrupt */ + BOD_IRQn = 23, /*!< Brown-Out Detect Interrupt */ + USB_IRQn = 24, /*!< USB Interrupt */ + CAN_IRQn = 25, /*!< CAN Interrupt */ + DMA_IRQn = 26, /*!< General Purpose DMA Interrupt */ + I2S_IRQn = 27, /*!< I2S Interrupt */ + ENET_IRQn = 28, /*!< Ethernet Interrupt */ + RIT_IRQn = 29, /*!< Repetitive Interrupt Timer Interrupt */ + MCPWM_IRQn = 30, /*!< Motor Control PWM Interrupt */ + QEI_IRQn = 31, /*!< Quadrature Encoder Interface Interrupt */ + PLL1_IRQn = 32, /*!< PLL1 Lock (USB PLL) Interrupt */ + USBActivity_IRQn = 33, /* USB Activity interrupt */ + CANActivity_IRQn = 34, /* CAN Activity interrupt */ +} IRQn_Type; + + +/* + * ========================================================================== + * ----------- Processor and Core Peripheral Section ------------------------ + * ========================================================================== + */ + +/* Configuration of the Cortex-M3 Processor and Core Peripherals */ +#define __MPU_PRESENT 1 /*!< MPU present or not */ +#define __NVIC_PRIO_BITS 5 /*!< Number of Bits used for Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + + +#include "core_cm3.h" /* Cortex-M3 processor and core peripherals */ +#include "system_LPC17xx.h" /* System Header */ + + +/******************************************************************************/ +/* Device Specific Peripheral registers structures */ +/******************************************************************************/ + +#if defined ( __CC_ARM ) +#pragma anon_unions +#endif + +/*------------- System Control (SC) ------------------------------------------*/ +typedef struct +{ + __IO uint32_t FLASHCFG; /* Flash Accelerator Module */ + uint32_t RESERVED0[31]; + __IO uint32_t PLL0CON; /* Clocking and Power Control */ + __IO uint32_t PLL0CFG; + __I uint32_t PLL0STAT; + __O uint32_t PLL0FEED; + uint32_t RESERVED1[4]; + __IO uint32_t PLL1CON; + __IO uint32_t PLL1CFG; + __I uint32_t PLL1STAT; + __O uint32_t PLL1FEED; + uint32_t RESERVED2[4]; + __IO uint32_t PCON; + __IO uint32_t PCONP; + uint32_t RESERVED3[15]; + __IO uint32_t CCLKCFG; + __IO uint32_t USBCLKCFG; + __IO uint32_t CLKSRCSEL; + __IO uint32_t CANSLEEPCLR; + __IO uint32_t CANWAKEFLAGS; + uint32_t RESERVED4[10]; + __IO uint32_t EXTINT; /* External Interrupts */ + uint32_t RESERVED5; + __IO uint32_t EXTMODE; + __IO uint32_t EXTPOLAR; + uint32_t RESERVED6[12]; + __IO uint32_t RSID; /* Reset */ + uint32_t RESERVED7[7]; + __IO uint32_t SCS; /* Syscon Miscellaneous Registers */ + __IO uint32_t IRCTRIM; /* Clock Dividers */ + __IO uint32_t PCLKSEL0; + __IO uint32_t PCLKSEL1; + uint32_t RESERVED8[4]; + __IO uint32_t USBIntSt; /* USB Device/OTG Interrupt Register */ + __IO uint32_t DMAREQSEL; + __IO uint32_t CLKOUTCFG; /* Clock Output Configuration */ + } LPC_SC_TypeDef; + +/*------------- Pin Connect Block (PINCON) -----------------------------------*/ +typedef struct +{ + __IO uint32_t PINSEL0; + __IO uint32_t PINSEL1; + __IO uint32_t PINSEL2; + __IO uint32_t PINSEL3; + __IO uint32_t PINSEL4; + __IO uint32_t PINSEL5; + __IO uint32_t PINSEL6; + __IO uint32_t PINSEL7; + __IO uint32_t PINSEL8; + __IO uint32_t PINSEL9; + __IO uint32_t PINSEL10; + uint32_t RESERVED0[5]; + __IO uint32_t PINMODE0; + __IO uint32_t PINMODE1; + __IO uint32_t PINMODE2; + __IO uint32_t PINMODE3; + __IO uint32_t PINMODE4; + __IO uint32_t PINMODE5; + __IO uint32_t PINMODE6; + __IO uint32_t PINMODE7; + __IO uint32_t PINMODE8; + __IO uint32_t PINMODE9; + __IO uint32_t PINMODE_OD0; + __IO uint32_t PINMODE_OD1; + __IO uint32_t PINMODE_OD2; + __IO uint32_t PINMODE_OD3; + __IO uint32_t PINMODE_OD4; + __IO uint32_t I2CPADCFG; +} LPC_PINCON_TypeDef; + +/*------------- General Purpose Input/Output (GPIO) --------------------------*/ +typedef struct +{ + union { + __IO uint32_t FIODIR; + struct { + __IO uint16_t FIODIRL; + __IO uint16_t FIODIRH; + }; + struct { + __IO uint8_t FIODIR0; + __IO uint8_t FIODIR1; + __IO uint8_t FIODIR2; + __IO uint8_t FIODIR3; + }; + }; + uint32_t RESERVED0[3]; + union { + __IO uint32_t FIOMASK; + struct { + __IO uint16_t FIOMASKL; + __IO uint16_t FIOMASKH; + }; + struct { + __IO uint8_t FIOMASK0; + __IO uint8_t FIOMASK1; + __IO uint8_t FIOMASK2; + __IO uint8_t FIOMASK3; + }; + }; + union { + __IO uint32_t FIOPIN; + struct { + __IO uint16_t FIOPINL; + __IO uint16_t FIOPINH; + }; + struct { + __IO uint8_t FIOPIN0; + __IO uint8_t FIOPIN1; + __IO uint8_t FIOPIN2; + __IO uint8_t FIOPIN3; + }; + }; + union { + __IO uint32_t FIOSET; + struct { + __IO uint16_t FIOSETL; + __IO uint16_t FIOSETH; + }; + struct { + __IO uint8_t FIOSET0; + __IO uint8_t FIOSET1; + __IO uint8_t FIOSET2; + __IO uint8_t FIOSET3; + }; + }; + union { + __O uint32_t FIOCLR; + struct { + __O uint16_t FIOCLRL; + __O uint16_t FIOCLRH; + }; + struct { + __O uint8_t FIOCLR0; + __O uint8_t FIOCLR1; + __O uint8_t FIOCLR2; + __O uint8_t FIOCLR3; + }; + }; +} LPC_GPIO_TypeDef; + +typedef struct +{ + __I uint32_t IntStatus; + __I uint32_t IO0IntStatR; + __I uint32_t IO0IntStatF; + __O uint32_t IO0IntClr; + __IO uint32_t IO0IntEnR; + __IO uint32_t IO0IntEnF; + uint32_t RESERVED0[3]; + __I uint32_t IO2IntStatR; + __I uint32_t IO2IntStatF; + __O uint32_t IO2IntClr; + __IO uint32_t IO2IntEnR; + __IO uint32_t IO2IntEnF; +} LPC_GPIOINT_TypeDef; + +/*------------- Timer (TIM) --------------------------------------------------*/ +typedef struct +{ + __IO uint32_t IR; + __IO uint32_t TCR; + __IO uint32_t TC; + __IO uint32_t PR; + __IO uint32_t PC; + __IO uint32_t MCR; + __IO uint32_t MR0; + __IO uint32_t MR1; + __IO uint32_t MR2; + __IO uint32_t MR3; + __IO uint32_t CCR; + __I uint32_t CR0; + __I uint32_t CR1; + uint32_t RESERVED0[2]; + __IO uint32_t EMR; + uint32_t RESERVED1[12]; + __IO uint32_t CTCR; +} LPC_TIM_TypeDef; + +/*------------- Pulse-Width Modulation (PWM) ---------------------------------*/ +typedef struct +{ + __IO uint32_t IR; + __IO uint32_t TCR; + __IO uint32_t TC; + __IO uint32_t PR; + __IO uint32_t PC; + __IO uint32_t MCR; + __IO uint32_t MR0; + __IO uint32_t MR1; + __IO uint32_t MR2; + __IO uint32_t MR3; + __IO uint32_t CCR; + __I uint32_t CR0; + __I uint32_t CR1; + __I uint32_t CR2; + __I uint32_t CR3; + uint32_t RESERVED0; + __IO uint32_t MR4; + __IO uint32_t MR5; + __IO uint32_t MR6; + __IO uint32_t PCR; + __IO uint32_t LER; + uint32_t RESERVED1[7]; + __IO uint32_t CTCR; +} LPC_PWM_TypeDef; + +/*------------- Universal Asynchronous Receiver Transmitter (UART) -----------*/ +typedef struct +{ + union { + __I uint8_t RBR; + __O uint8_t THR; + __IO uint8_t DLL; + uint32_t RESERVED0; + }; + union { + __IO uint8_t DLM; + __IO uint32_t IER; + }; + union { + __I uint32_t IIR; + __O uint8_t FCR; + }; + __IO uint8_t LCR; + uint8_t RESERVED1[7]; + __I uint8_t LSR; + uint8_t RESERVED2[7]; + __IO uint8_t SCR; + uint8_t RESERVED3[3]; + __IO uint32_t ACR; + __IO uint8_t ICR; + uint8_t RESERVED4[3]; + __IO uint8_t FDR; + uint8_t RESERVED5[7]; + __IO uint8_t TER; + uint8_t RESERVED6[39]; + __IO uint32_t FIFOLVL; +} LPC_UART_TypeDef; + +typedef struct +{ + union { + __I uint8_t RBR; + __O uint8_t THR; + __IO uint8_t DLL; + uint32_t RESERVED0; + }; + union { + __IO uint8_t DLM; + __IO uint32_t IER; + }; + union { + __I uint32_t IIR; + __O uint8_t FCR; + }; + __IO uint8_t LCR; + uint8_t RESERVED1[7]; + __I uint8_t LSR; + uint8_t RESERVED2[7]; + __IO uint8_t SCR; + uint8_t RESERVED3[3]; + __IO uint32_t ACR; + __IO uint8_t ICR; + uint8_t RESERVED4[3]; + __IO uint8_t FDR; + uint8_t RESERVED5[7]; + __IO uint8_t TER; + uint8_t RESERVED6[39]; + __IO uint32_t FIFOLVL; +} LPC_UART0_TypeDef; + +typedef struct +{ + union { + __I uint8_t RBR; + __O uint8_t THR; + __IO uint8_t DLL; + uint32_t RESERVED0; + }; + union { + __IO uint8_t DLM; + __IO uint32_t IER; + }; + union { + __I uint32_t IIR; + __O uint8_t FCR; + }; + __IO uint8_t LCR; + uint8_t RESERVED1[3]; + __IO uint8_t MCR; + uint8_t RESERVED2[3]; + __I uint8_t LSR; + uint8_t RESERVED3[3]; + __I uint8_t MSR; + uint8_t RESERVED4[3]; + __IO uint8_t SCR; + uint8_t RESERVED5[3]; + __IO uint32_t ACR; + uint32_t RESERVED6; + __IO uint32_t FDR; + uint32_t RESERVED7; + __IO uint8_t TER; + uint8_t RESERVED8[27]; + __IO uint8_t RS485CTRL; + uint8_t RESERVED9[3]; + __IO uint8_t ADRMATCH; + uint8_t RESERVED10[3]; + __IO uint8_t RS485DLY; + uint8_t RESERVED11[3]; + __IO uint32_t FIFOLVL; +} LPC_UART1_TypeDef; + +/*------------- Serial Peripheral Interface (SPI) ----------------------------*/ +typedef struct +{ + __IO uint32_t SPCR; + __I uint32_t SPSR; + __IO uint32_t SPDR; + __IO uint32_t SPCCR; + uint32_t RESERVED0[3]; + __IO uint32_t SPINT; +} LPC_SPI_TypeDef; + +/*------------- Synchronous Serial Communication (SSP) -----------------------*/ +typedef struct +{ + __IO uint32_t CR0; + __IO uint32_t CR1; + __IO uint32_t DR; + __I uint32_t SR; + __IO uint32_t CPSR; + __IO uint32_t IMSC; + __IO uint32_t RIS; + __IO uint32_t MIS; + __IO uint32_t ICR; + __IO uint32_t DMACR; +} LPC_SSP_TypeDef; + +/*------------- Inter-Integrated Circuit (I2C) -------------------------------*/ +typedef struct +{ + __IO uint32_t I2CONSET; + __I uint32_t I2STAT; + __IO uint32_t I2DAT; + __IO uint32_t I2ADR0; + __IO uint32_t I2SCLH; + __IO uint32_t I2SCLL; + __O uint32_t I2CONCLR; + __IO uint32_t MMCTRL; + __IO uint32_t I2ADR1; + __IO uint32_t I2ADR2; + __IO uint32_t I2ADR3; + __I uint32_t I2DATA_BUFFER; + __IO uint32_t I2MASK0; + __IO uint32_t I2MASK1; + __IO uint32_t I2MASK2; + __IO uint32_t I2MASK3; +} LPC_I2C_TypeDef; + +/*------------- Inter IC Sound (I2S) -----------------------------------------*/ +typedef struct +{ + __IO uint32_t I2SDAO; + __IO uint32_t I2SDAI; + __O uint32_t I2STXFIFO; + __I uint32_t I2SRXFIFO; + __I uint32_t I2SSTATE; + __IO uint32_t I2SDMA1; + __IO uint32_t I2SDMA2; + __IO uint32_t I2SIRQ; + __IO uint32_t I2STXRATE; + __IO uint32_t I2SRXRATE; + __IO uint32_t I2STXBITRATE; + __IO uint32_t I2SRXBITRATE; + __IO uint32_t I2STXMODE; + __IO uint32_t I2SRXMODE; +} LPC_I2S_TypeDef; + +/*------------- Repetitive Interrupt Timer (RIT) -----------------------------*/ +typedef struct +{ + __IO uint32_t RICOMPVAL; + __IO uint32_t RIMASK; + __IO uint8_t RICTRL; + uint8_t RESERVED0[3]; + __IO uint32_t RICOUNTER; +} LPC_RIT_TypeDef; + +/*------------- Real-Time Clock (RTC) ----------------------------------------*/ +typedef struct +{ + __IO uint8_t ILR; + uint8_t RESERVED0[7]; + __IO uint8_t CCR; + uint8_t RESERVED1[3]; + __IO uint8_t CIIR; + uint8_t RESERVED2[3]; + __IO uint8_t AMR; + uint8_t RESERVED3[3]; + __I uint32_t CTIME0; + __I uint32_t CTIME1; + __I uint32_t CTIME2; + __IO uint8_t SEC; + uint8_t RESERVED4[3]; + __IO uint8_t MIN; + uint8_t RESERVED5[3]; + __IO uint8_t HOUR; + uint8_t RESERVED6[3]; + __IO uint8_t DOM; + uint8_t RESERVED7[3]; + __IO uint8_t DOW; + uint8_t RESERVED8[3]; + __IO uint16_t DOY; + uint16_t RESERVED9; + __IO uint8_t MONTH; + uint8_t RESERVED10[3]; + __IO uint16_t YEAR; + uint16_t RESERVED11; + __IO uint32_t CALIBRATION; + __IO uint32_t GPREG0; + __IO uint32_t GPREG1; + __IO uint32_t GPREG2; + __IO uint32_t GPREG3; + __IO uint32_t GPREG4; + __IO uint8_t RTC_AUXEN; + uint8_t RESERVED12[3]; + __IO uint8_t RTC_AUX; + uint8_t RESERVED13[3]; + __IO uint8_t ALSEC; + uint8_t RESERVED14[3]; + __IO uint8_t ALMIN; + uint8_t RESERVED15[3]; + __IO uint8_t ALHOUR; + uint8_t RESERVED16[3]; + __IO uint8_t ALDOM; + uint8_t RESERVED17[3]; + __IO uint8_t ALDOW; + uint8_t RESERVED18[3]; + __IO uint16_t ALDOY; + uint16_t RESERVED19; + __IO uint8_t ALMON; + uint8_t RESERVED20[3]; + __IO uint16_t ALYEAR; + uint16_t RESERVED21; +} LPC_RTC_TypeDef; + +/*------------- Watchdog Timer (WDT) -----------------------------------------*/ +typedef struct +{ + __IO uint8_t WDMOD; + uint8_t RESERVED0[3]; + __IO uint32_t WDTC; + __O uint8_t WDFEED; + uint8_t RESERVED1[3]; + __I uint32_t WDTV; + __IO uint32_t WDCLKSEL; +} LPC_WDT_TypeDef; + +/*------------- Analog-to-Digital Converter (ADC) ----------------------------*/ +typedef struct +{ + __IO uint32_t ADCR; + __IO uint32_t ADGDR; + uint32_t RESERVED0; + __IO uint32_t ADINTEN; + __I uint32_t ADDR0; + __I uint32_t ADDR1; + __I uint32_t ADDR2; + __I uint32_t ADDR3; + __I uint32_t ADDR4; + __I uint32_t ADDR5; + __I uint32_t ADDR6; + __I uint32_t ADDR7; + __I uint32_t ADSTAT; + __IO uint32_t ADTRM; +} LPC_ADC_TypeDef; + +/*------------- Digital-to-Analog Converter (DAC) ----------------------------*/ +typedef struct +{ + __IO uint32_t DACR; + __IO uint32_t DACCTRL; + __IO uint16_t DACCNTVAL; +} LPC_DAC_TypeDef; + +/*------------- Motor Control Pulse-Width Modulation (MCPWM) -----------------*/ +typedef struct +{ + __I uint32_t MCCON; + __O uint32_t MCCON_SET; + __O uint32_t MCCON_CLR; + __I uint32_t MCCAPCON; + __O uint32_t MCCAPCON_SET; + __O uint32_t MCCAPCON_CLR; + __IO uint32_t MCTIM0; + __IO uint32_t MCTIM1; + __IO uint32_t MCTIM2; + __IO uint32_t MCPER0; + __IO uint32_t MCPER1; + __IO uint32_t MCPER2; + __IO uint32_t MCPW0; + __IO uint32_t MCPW1; + __IO uint32_t MCPW2; + __IO uint32_t MCDEADTIME; + __IO uint32_t MCCCP; + __IO uint32_t MCCR0; + __IO uint32_t MCCR1; + __IO uint32_t MCCR2; + __I uint32_t MCINTEN; + __O uint32_t MCINTEN_SET; + __O uint32_t MCINTEN_CLR; + __I uint32_t MCCNTCON; + __O uint32_t MCCNTCON_SET; + __O uint32_t MCCNTCON_CLR; + __I uint32_t MCINTFLAG; + __O uint32_t MCINTFLAG_SET; + __O uint32_t MCINTFLAG_CLR; + __O uint32_t MCCAP_CLR; +} LPC_MCPWM_TypeDef; + +/*------------- Quadrature Encoder Interface (QEI) ---------------------------*/ +typedef struct +{ + __O uint32_t QEICON; + __I uint32_t QEISTAT; + __IO uint32_t QEICONF; + __I uint32_t QEIPOS; + __IO uint32_t QEIMAXPOS; + __IO uint32_t CMPOS0; + __IO uint32_t CMPOS1; + __IO uint32_t CMPOS2; + __I uint32_t INXCNT; + __IO uint32_t INXCMP; + __IO uint32_t QEILOAD; + __I uint32_t QEITIME; + __I uint32_t QEIVEL; + __I uint32_t QEICAP; + __IO uint32_t VELCOMP; + __IO uint32_t FILTER; + uint32_t RESERVED0[998]; + __O uint32_t QEIIEC; + __O uint32_t QEIIES; + __I uint32_t QEIINTSTAT; + __I uint32_t QEIIE; + __O uint32_t QEICLR; + __O uint32_t QEISET; +} LPC_QEI_TypeDef; + +/*------------- Controller Area Network (CAN) --------------------------------*/ +typedef struct +{ + __IO uint32_t mask[512]; /* ID Masks */ +} LPC_CANAF_RAM_TypeDef; + +typedef struct /* Acceptance Filter Registers */ +{ + __IO uint32_t AFMR; + __IO uint32_t SFF_sa; + __IO uint32_t SFF_GRP_sa; + __IO uint32_t EFF_sa; + __IO uint32_t EFF_GRP_sa; + __IO uint32_t ENDofTable; + __I uint32_t LUTerrAd; + __I uint32_t LUTerr; + __IO uint32_t FCANIE; + __IO uint32_t FCANIC0; + __IO uint32_t FCANIC1; +} LPC_CANAF_TypeDef; + +typedef struct /* Central Registers */ +{ + __I uint32_t CANTxSR; + __I uint32_t CANRxSR; + __I uint32_t CANMSR; +} LPC_CANCR_TypeDef; + +typedef struct /* Controller Registers */ +{ + __IO uint32_t MOD; + __O uint32_t CMR; + __IO uint32_t GSR; + __I uint32_t ICR; + __IO uint32_t IER; + __IO uint32_t BTR; + __IO uint32_t EWL; + __I uint32_t SR; + __IO uint32_t RFS; + __IO uint32_t RID; + __IO uint32_t RDA; + __IO uint32_t RDB; + __IO uint32_t TFI1; + __IO uint32_t TID1; + __IO uint32_t TDA1; + __IO uint32_t TDB1; + __IO uint32_t TFI2; + __IO uint32_t TID2; + __IO uint32_t TDA2; + __IO uint32_t TDB2; + __IO uint32_t TFI3; + __IO uint32_t TID3; + __IO uint32_t TDA3; + __IO uint32_t TDB3; +} LPC_CAN_TypeDef; + +/*------------- General Purpose Direct Memory Access (GPDMA) -----------------*/ +typedef struct /* Common Registers */ +{ + __I uint32_t DMACIntStat; + __I uint32_t DMACIntTCStat; + __O uint32_t DMACIntTCClear; + __I uint32_t DMACIntErrStat; + __O uint32_t DMACIntErrClr; + __I uint32_t DMACRawIntTCStat; + __I uint32_t DMACRawIntErrStat; + __I uint32_t DMACEnbldChns; + __IO uint32_t DMACSoftBReq; + __IO uint32_t DMACSoftSReq; + __IO uint32_t DMACSoftLBReq; + __IO uint32_t DMACSoftLSReq; + __IO uint32_t DMACConfig; + __IO uint32_t DMACSync; +} LPC_GPDMA_TypeDef; + +typedef struct /* Channel Registers */ +{ + __IO uint32_t DMACCSrcAddr; + __IO uint32_t DMACCDestAddr; + __IO uint32_t DMACCLLI; + __IO uint32_t DMACCControl; + __IO uint32_t DMACCConfig; +} LPC_GPDMACH_TypeDef; + +/*------------- Universal Serial Bus (USB) -----------------------------------*/ +typedef struct +{ + __I uint32_t HcRevision; /* USB Host Registers */ + __IO uint32_t HcControl; + __IO uint32_t HcCommandStatus; + __IO uint32_t HcInterruptStatus; + __IO uint32_t HcInterruptEnable; + __IO uint32_t HcInterruptDisable; + __IO uint32_t HcHCCA; + __I uint32_t HcPeriodCurrentED; + __IO uint32_t HcControlHeadED; + __IO uint32_t HcControlCurrentED; + __IO uint32_t HcBulkHeadED; + __IO uint32_t HcBulkCurrentED; + __I uint32_t HcDoneHead; + __IO uint32_t HcFmInterval; + __I uint32_t HcFmRemaining; + __I uint32_t HcFmNumber; + __IO uint32_t HcPeriodicStart; + __IO uint32_t HcLSTreshold; + __IO uint32_t HcRhDescriptorA; + __IO uint32_t HcRhDescriptorB; + __IO uint32_t HcRhStatus; + __IO uint32_t HcRhPortStatus1; + __IO uint32_t HcRhPortStatus2; + uint32_t RESERVED0[40]; + __I uint32_t Module_ID; + + __I uint32_t OTGIntSt; /* USB On-The-Go Registers */ + __IO uint32_t OTGIntEn; + __O uint32_t OTGIntSet; + __O uint32_t OTGIntClr; + __IO uint32_t OTGStCtrl; + __IO uint32_t OTGTmr; + uint32_t RESERVED1[58]; + + __I uint32_t USBDevIntSt; /* USB Device Interrupt Registers */ + __IO uint32_t USBDevIntEn; + __O uint32_t USBDevIntClr; + __O uint32_t USBDevIntSet; + + __O uint32_t USBCmdCode; /* USB Device SIE Command Registers */ + __I uint32_t USBCmdData; + + __I uint32_t USBRxData; /* USB Device Transfer Registers */ + __O uint32_t USBTxData; + __I uint32_t USBRxPLen; + __O uint32_t USBTxPLen; + __IO uint32_t USBCtrl; + __O uint32_t USBDevIntPri; + + __I uint32_t USBEpIntSt; /* USB Device Endpoint Interrupt Regs */ + __IO uint32_t USBEpIntEn; + __O uint32_t USBEpIntClr; + __O uint32_t USBEpIntSet; + __O uint32_t USBEpIntPri; + + __IO uint32_t USBReEp; /* USB Device Endpoint Realization Reg*/ + __O uint32_t USBEpInd; + __IO uint32_t USBMaxPSize; + + __I uint32_t USBDMARSt; /* USB Device DMA Registers */ + __O uint32_t USBDMARClr; + __O uint32_t USBDMARSet; + uint32_t RESERVED2[9]; + __IO uint32_t USBUDCAH; + __I uint32_t USBEpDMASt; + __O uint32_t USBEpDMAEn; + __O uint32_t USBEpDMADis; + __I uint32_t USBDMAIntSt; + __IO uint32_t USBDMAIntEn; + uint32_t RESERVED3[2]; + __I uint32_t USBEoTIntSt; + __O uint32_t USBEoTIntClr; + __O uint32_t USBEoTIntSet; + __I uint32_t USBNDDRIntSt; + __O uint32_t USBNDDRIntClr; + __O uint32_t USBNDDRIntSet; + __I uint32_t USBSysErrIntSt; + __O uint32_t USBSysErrIntClr; + __O uint32_t USBSysErrIntSet; + uint32_t RESERVED4[15]; + + union { + __I uint32_t I2C_RX; /* USB OTG I2C Registers */ + __O uint32_t I2C_TX; + }; + __I uint32_t I2C_STS; + __IO uint32_t I2C_CTL; + __IO uint32_t I2C_CLKHI; + __O uint32_t I2C_CLKLO; + uint32_t RESERVED5[824]; + + union { + __IO uint32_t USBClkCtrl; /* USB Clock Control Registers */ + __IO uint32_t OTGClkCtrl; + }; + union { + __I uint32_t USBClkSt; + __I uint32_t OTGClkSt; + }; +} LPC_USB_TypeDef; + +/*------------- Ethernet Media Access Controller (EMAC) ----------------------*/ +typedef struct +{ + __IO uint32_t MAC1; /* MAC Registers */ + __IO uint32_t MAC2; + __IO uint32_t IPGT; + __IO uint32_t IPGR; + __IO uint32_t CLRT; + __IO uint32_t MAXF; + __IO uint32_t SUPP; + __IO uint32_t TEST; + __IO uint32_t MCFG; + __IO uint32_t MCMD; + __IO uint32_t MADR; + __O uint32_t MWTD; + __I uint32_t MRDD; + __I uint32_t MIND; + uint32_t RESERVED0[2]; + __IO uint32_t SA0; + __IO uint32_t SA1; + __IO uint32_t SA2; + uint32_t RESERVED1[45]; + __IO uint32_t Command; /* Control Registers */ + __I uint32_t Status; + __IO uint32_t RxDescriptor; + __IO uint32_t RxStatus; + __IO uint32_t RxDescriptorNumber; + __I uint32_t RxProduceIndex; + __IO uint32_t RxConsumeIndex; + __IO uint32_t TxDescriptor; + __IO uint32_t TxStatus; + __IO uint32_t TxDescriptorNumber; + __IO uint32_t TxProduceIndex; + __I uint32_t TxConsumeIndex; + uint32_t RESERVED2[10]; + __I uint32_t TSV0; + __I uint32_t TSV1; + __I uint32_t RSV; + uint32_t RESERVED3[3]; + __IO uint32_t FlowControlCounter; + __I uint32_t FlowControlStatus; + uint32_t RESERVED4[34]; + __IO uint32_t RxFilterCtrl; /* Rx Filter Registers */ + __IO uint32_t RxFilterWoLStatus; + __IO uint32_t RxFilterWoLClear; + uint32_t RESERVED5; + __IO uint32_t HashFilterL; + __IO uint32_t HashFilterH; + uint32_t RESERVED6[882]; + __I uint32_t IntStatus; /* Module Control Registers */ + __IO uint32_t IntEnable; + __O uint32_t IntClear; + __O uint32_t IntSet; + uint32_t RESERVED7; + __IO uint32_t PowerDown; + uint32_t RESERVED8; + __IO uint32_t Module_ID; +} LPC_EMAC_TypeDef; + +#if defined ( __CC_ARM ) +#pragma no_anon_unions +#endif + + +/******************************************************************************/ +/* Peripheral memory map */ +/******************************************************************************/ +/* Base addresses */ +#define LPC_FLASH_BASE (0x00000000UL) +#define LPC_RAM_BASE (0x10000000UL) +#define LPC_GPIO_BASE (0x2009C000UL) +#define LPC_APB0_BASE (0x40000000UL) +#define LPC_APB1_BASE (0x40080000UL) +#define LPC_AHB_BASE (0x50000000UL) +#define LPC_CM3_BASE (0xE0000000UL) + +/* APB0 peripherals */ +#define LPC_WDT_BASE (LPC_APB0_BASE + 0x00000) +#define LPC_TIM0_BASE (LPC_APB0_BASE + 0x04000) +#define LPC_TIM1_BASE (LPC_APB0_BASE + 0x08000) +#define LPC_UART0_BASE (LPC_APB0_BASE + 0x0C000) +#define LPC_UART1_BASE (LPC_APB0_BASE + 0x10000) +#define LPC_PWM1_BASE (LPC_APB0_BASE + 0x18000) +#define LPC_I2C0_BASE (LPC_APB0_BASE + 0x1C000) +#define LPC_SPI_BASE (LPC_APB0_BASE + 0x20000) +#define LPC_RTC_BASE (LPC_APB0_BASE + 0x24000) +#define LPC_GPIOINT_BASE (LPC_APB0_BASE + 0x28080) +#define LPC_PINCON_BASE (LPC_APB0_BASE + 0x2C000) +#define LPC_SSP1_BASE (LPC_APB0_BASE + 0x30000) +#define LPC_ADC_BASE (LPC_APB0_BASE + 0x34000) +#define LPC_CANAF_RAM_BASE (LPC_APB0_BASE + 0x38000) +#define LPC_CANAF_BASE (LPC_APB0_BASE + 0x3C000) +#define LPC_CANCR_BASE (LPC_APB0_BASE + 0x40000) +#define LPC_CAN1_BASE (LPC_APB0_BASE + 0x44000) +#define LPC_CAN2_BASE (LPC_APB0_BASE + 0x48000) +#define LPC_I2C1_BASE (LPC_APB0_BASE + 0x5C000) + +/* APB1 peripherals */ +#define LPC_SSP0_BASE (LPC_APB1_BASE + 0x08000) +#define LPC_DAC_BASE (LPC_APB1_BASE + 0x0C000) +#define LPC_TIM2_BASE (LPC_APB1_BASE + 0x10000) +#define LPC_TIM3_BASE (LPC_APB1_BASE + 0x14000) +#define LPC_UART2_BASE (LPC_APB1_BASE + 0x18000) +#define LPC_UART3_BASE (LPC_APB1_BASE + 0x1C000) +#define LPC_I2C2_BASE (LPC_APB1_BASE + 0x20000) +#define LPC_I2S_BASE (LPC_APB1_BASE + 0x28000) +#define LPC_RIT_BASE (LPC_APB1_BASE + 0x30000) +#define LPC_MCPWM_BASE (LPC_APB1_BASE + 0x38000) +#define LPC_QEI_BASE (LPC_APB1_BASE + 0x3C000) +#define LPC_SC_BASE (LPC_APB1_BASE + 0x7C000) + +/* AHB peripherals */ +#define LPC_EMAC_BASE (LPC_AHB_BASE + 0x00000) +#define LPC_GPDMA_BASE (LPC_AHB_BASE + 0x04000) +#define LPC_GPDMACH0_BASE (LPC_AHB_BASE + 0x04100) +#define LPC_GPDMACH1_BASE (LPC_AHB_BASE + 0x04120) +#define LPC_GPDMACH2_BASE (LPC_AHB_BASE + 0x04140) +#define LPC_GPDMACH3_BASE (LPC_AHB_BASE + 0x04160) +#define LPC_GPDMACH4_BASE (LPC_AHB_BASE + 0x04180) +#define LPC_GPDMACH5_BASE (LPC_AHB_BASE + 0x041A0) +#define LPC_GPDMACH6_BASE (LPC_AHB_BASE + 0x041C0) +#define LPC_GPDMACH7_BASE (LPC_AHB_BASE + 0x041E0) +#define LPC_USB_BASE (LPC_AHB_BASE + 0x0C000) + +/* GPIOs */ +#define LPC_GPIO0_BASE (LPC_GPIO_BASE + 0x00000) +#define LPC_GPIO1_BASE (LPC_GPIO_BASE + 0x00020) +#define LPC_GPIO2_BASE (LPC_GPIO_BASE + 0x00040) +#define LPC_GPIO3_BASE (LPC_GPIO_BASE + 0x00060) +#define LPC_GPIO4_BASE (LPC_GPIO_BASE + 0x00080) + + +/******************************************************************************/ +/* Peripheral declaration */ +/******************************************************************************/ +#define LPC_SC ((LPC_SC_TypeDef *) LPC_SC_BASE ) +#define LPC_GPIO0 ((LPC_GPIO_TypeDef *) LPC_GPIO0_BASE ) +#define LPC_GPIO1 ((LPC_GPIO_TypeDef *) LPC_GPIO1_BASE ) +#define LPC_GPIO2 ((LPC_GPIO_TypeDef *) LPC_GPIO2_BASE ) +#define LPC_GPIO3 ((LPC_GPIO_TypeDef *) LPC_GPIO3_BASE ) +#define LPC_GPIO4 ((LPC_GPIO_TypeDef *) LPC_GPIO4_BASE ) +#define LPC_WDT ((LPC_WDT_TypeDef *) LPC_WDT_BASE ) +#define LPC_TIM0 ((LPC_TIM_TypeDef *) LPC_TIM0_BASE ) +#define LPC_TIM1 ((LPC_TIM_TypeDef *) LPC_TIM1_BASE ) +#define LPC_TIM2 ((LPC_TIM_TypeDef *) LPC_TIM2_BASE ) +#define LPC_TIM3 ((LPC_TIM_TypeDef *) LPC_TIM3_BASE ) +#define LPC_RIT ((LPC_RIT_TypeDef *) LPC_RIT_BASE ) +#define LPC_UART0 ((LPC_UART0_TypeDef *) LPC_UART0_BASE ) +#define LPC_UART1 ((LPC_UART1_TypeDef *) LPC_UART1_BASE ) +#define LPC_UART2 ((LPC_UART_TypeDef *) LPC_UART2_BASE ) +#define LPC_UART3 ((LPC_UART_TypeDef *) LPC_UART3_BASE ) +#define LPC_PWM1 ((LPC_PWM_TypeDef *) LPC_PWM1_BASE ) +#define LPC_I2C0 ((LPC_I2C_TypeDef *) LPC_I2C0_BASE ) +#define LPC_I2C1 ((LPC_I2C_TypeDef *) LPC_I2C1_BASE ) +#define LPC_I2C2 ((LPC_I2C_TypeDef *) LPC_I2C2_BASE ) +#define LPC_I2S ((LPC_I2S_TypeDef *) LPC_I2S_BASE ) +#define LPC_SPI ((LPC_SPI_TypeDef *) LPC_SPI_BASE ) +#define LPC_RTC ((LPC_RTC_TypeDef *) LPC_RTC_BASE ) +#define LPC_GPIOINT ((LPC_GPIOINT_TypeDef *) LPC_GPIOINT_BASE ) +#define LPC_PINCON ((LPC_PINCON_TypeDef *) LPC_PINCON_BASE ) +#define LPC_SSP0 ((LPC_SSP_TypeDef *) LPC_SSP0_BASE ) +#define LPC_SSP1 ((LPC_SSP_TypeDef *) LPC_SSP1_BASE ) +#define LPC_ADC ((LPC_ADC_TypeDef *) LPC_ADC_BASE ) +#define LPC_DAC ((LPC_DAC_TypeDef *) LPC_DAC_BASE ) +#define LPC_CANAF_RAM ((LPC_CANAF_RAM_TypeDef *) LPC_CANAF_RAM_BASE) +#define LPC_CANAF ((LPC_CANAF_TypeDef *) LPC_CANAF_BASE ) +#define LPC_CANCR ((LPC_CANCR_TypeDef *) LPC_CANCR_BASE ) +#define LPC_CAN1 ((LPC_CAN_TypeDef *) LPC_CAN1_BASE ) +#define LPC_CAN2 ((LPC_CAN_TypeDef *) LPC_CAN2_BASE ) +#define LPC_MCPWM ((LPC_MCPWM_TypeDef *) LPC_MCPWM_BASE ) +#define LPC_QEI ((LPC_QEI_TypeDef *) LPC_QEI_BASE ) +#define LPC_EMAC ((LPC_EMAC_TypeDef *) LPC_EMAC_BASE ) +#define LPC_GPDMA ((LPC_GPDMA_TypeDef *) LPC_GPDMA_BASE ) +#define LPC_GPDMACH0 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH0_BASE ) +#define LPC_GPDMACH1 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH1_BASE ) +#define LPC_GPDMACH2 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH2_BASE ) +#define LPC_GPDMACH3 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH3_BASE ) +#define LPC_GPDMACH4 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH4_BASE ) +#define LPC_GPDMACH5 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH5_BASE ) +#define LPC_GPDMACH6 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH6_BASE ) +#define LPC_GPDMACH7 ((LPC_GPDMACH_TypeDef *) LPC_GPDMACH7_BASE ) +#define LPC_USB ((LPC_USB_TypeDef *) LPC_USB_BASE ) + +#endif // __LPC17xx_H__
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/cmsis.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/cmsis.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,17 @@ +/* mbed Microcontroller Library - CMSIS + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * A generic CMSIS include header, pulling in LPC1768 specifics + */ + +#ifndef MBED_CMSIS_H +#define MBED_CMSIS_H + +#ifndef TARGET_LPC1768 +#define TARGET_LPC1768 +#endif + +#include "LPC17xx.h" +#include "cmsis_nvic.h" + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/cmsis_nvic.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/cmsis_nvic.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,23 @@ +/* mbed Microcontroller Library - cmsis_nvic + * Copyright (c) 2009-2011 ARM Limited. All rights reserved. + * + * CMSIS-style functionality to support dynamic vectors + */ + +#ifndef MBED_CMSIS_NVIC_H +#define MBED_CMSIS_NVIC_H + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector); +uint32_t NVIC_GetVector(IRQn_Type IRQn); + +#ifdef __cplusplus +} +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/core_cm3.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/core_cm3.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,1550 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V3.01 + * @date 06. March 2012 + * + * @note + * Copyright (C) 2009-2012 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ +#if defined ( __ICCARM__ ) + #pragma system_include /* treat file as system include file for MISRA check */ +#endif + +#ifdef __cplusplus + extern "C" { +#endif + +#ifndef __CORE_CM3_H_GENERIC +#define __CORE_CM3_H_GENERIC + +/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions + CMSIS violates the following MISRA-C:2004 rules: + + \li Required Rule 8.5, object/function definition in header file.<br> + Function definitions in header files are used to allow 'inlining'. + + \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br> + Unions are used for effective representation of core registers. + + \li Advisory Rule 19.7, Function-like macro defined.<br> + Function-like macros are used to allow more efficient code. + */ + + +/******************************************************************************* + * CMSIS definitions + ******************************************************************************/ +/** \ingroup Cortex_M3 + @{ + */ + +/* CMSIS CM3 definitions */ +#define __CM3_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x01) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | \ + __CM3_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex-M Core */ + + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + #define __STATIC_INLINE static __inline + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */ + #define __STATIC_INLINE static inline + +#elif defined ( __TMS470__ ) + #define __ASM __asm /*!< asm keyword for TI CCS Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + #define __STATIC_INLINE static inline + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + #define __STATIC_INLINE static inline + +#endif + +/** __FPU_USED indicates whether an FPU is used or not. This core does not support an FPU at all +*/ +#define __FPU_USED 0 + +#if defined ( __CC_ARM ) + #if defined __TARGET_FPU_VFP + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __ICCARM__ ) + #if defined __ARMVFP__ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TMS470__ ) + #if defined __TI__VFP_SUPPORT____ + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __GNUC__ ) + #if defined (__VFP_FP__) && !defined(__SOFTFP__) + #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" + #endif + +#elif defined ( __TASKING__ ) + /* add preprocessor checks */ +#endif + +#include <stdint.h> /* standard types definitions */ +#include <core_cmInstr.h> /* Core Instruction Access */ +#include <core_cmFunc.h> /* Core Function Access */ + +#endif /* __CORE_CM3_H_GENERIC */ + +#ifndef __CMSIS_GENERIC + +#ifndef __CORE_CM3_H_DEPENDANT +#define __CORE_CM3_H_DEPENDANT + +/* check device defines and use defaults */ +#if defined __CHECK_DEVICE_DEFINES + #ifndef __CM3_REV + #define __CM3_REV 0x0200 + #warning "__CM3_REV not defined in device header file; using default!" + #endif + + #ifndef __MPU_PRESENT + #define __MPU_PRESENT 0 + #warning "__MPU_PRESENT not defined in device header file; using default!" + #endif + + #ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 + #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" + #endif + + #ifndef __Vendor_SysTickConfig + #define __Vendor_SysTickConfig 0 + #warning "__Vendor_SysTickConfig not defined in device header file; using default!" + #endif +#endif + +/* IO definitions (access restrictions to peripheral registers) */ +/** + \defgroup CMSIS_glob_defs CMSIS Global Defines + + <strong>IO Type Qualifiers</strong> are used + \li to specify the access to peripheral variables. + \li for automatic generation of peripheral register debug information. +*/ +#ifdef __cplusplus + #define __I volatile /*!< Defines 'read only' permissions */ +#else + #define __I volatile const /*!< Defines 'read only' permissions */ +#endif +#define __O volatile /*!< Defines 'write only' permissions */ +#define __IO volatile /*!< Defines 'read / write' permissions */ + +/*@} end of group Cortex_M3 */ + + + +/******************************************************************************* + * Register Abstraction + Core Register contain: + - Core Register + - Core NVIC Register + - Core SCB Register + - Core SysTick Register + - Core Debug Register + - Core MPU Register + ******************************************************************************/ +/** \defgroup CMSIS_core_register Defines and Type Definitions + \brief Type definitions and defines for Cortex-M processor based devices. +*/ + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CORE Status and Control Registers + \brief Core Register type definitions. + @{ + */ + +/** \brief Union type to access the Application Program Status Register (APSR). + */ +typedef union +{ + struct + { +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ +#else + uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ +#endif + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} APSR_Type; + + +/** \brief Union type to access the Interrupt Program Status Register (IPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ + uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} IPSR_Type; + + +/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR). + */ +typedef union +{ + struct + { + uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ +#if (__CORTEX_M != 0x04) + uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ +#else + uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ + uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ + uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ +#endif + uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ + uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ + uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ + uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ + uint32_t C:1; /*!< bit: 29 Carry condition code flag */ + uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ + uint32_t N:1; /*!< bit: 31 Negative condition code flag */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} xPSR_Type; + + +/** \brief Union type to access the Control Registers (CONTROL). + */ +typedef union +{ + struct + { + uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ + uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ + uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ + uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ + } b; /*!< Structure used for bit access */ + uint32_t w; /*!< Type used for word access */ +} CONTROL_Type; + +/*@} end of group CMSIS_CORE */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) + \brief Type definitions for the NVIC Registers + @{ + */ + +/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ +} NVIC_Type; + +/* Software Triggered Interrupt Register Definitions */ +#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */ +#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */ + +/*@} end of group CMSIS_NVIC */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCB System Control Block (SCB) + \brief Type definitions for the System Control Block Registers + @{ + */ + +/** \brief Structure type to access the System Control Block (SCB). + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */ +#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Vector Table Offset Register Definitions */ +#if (__CM3_REV < 0x0201) /* core r2p1 */ +#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#else +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ +#endif + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ + +/*@} end of group CMSIS_SCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) + \brief Type definitions for the System Control and ID Register not in the SCB + @{ + */ + +/** \brief Structure type to access the System Control and ID Register not in the SCB. + */ +typedef struct +{ + uint32_t RESERVED0[1]; + __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ +#else + uint32_t RESERVED1[1]; +#endif +} SCnSCB_Type; + +/* Interrupt Controller Type Register Definitions */ +#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */ +#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ + +#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */ +#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ + +#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */ +#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ + +#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */ +#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */ + +/*@} end of group CMSIS_SCnotSCB */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_SysTick System Tick Timer (SysTick) + \brief Type definitions for the System Timer Registers. + @{ + */ + +/** \brief Structure type to access the System Timer (SysTick). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ + +/*@} end of group CMSIS_SysTick */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) + \brief Type definitions for the Instrumentation Trace Macrocell (ITM) + @{ + */ + +/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */ +#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_TXENA_Pos 3 /*!< ITM TCR: TXENA Position */ +#define ITM_TCR_TXENA_Msk (1UL << ITM_TCR_TXENA_Pos) /*!< ITM TCR: TXENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/*@}*/ /* end of group CMSIS_ITM */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) + \brief Type definitions for the Data Watchpoint and Trace (DWT) + @{ + */ + +/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT). + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ + __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ + __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ + __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ + __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ + __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ + __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ + __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ + __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ + __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ + __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ + uint32_t RESERVED0[1]; + __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ + __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ + __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ + uint32_t RESERVED1[1]; + __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ + __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ + __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ + uint32_t RESERVED2[1]; + __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ + __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ + __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ +} DWT_Type; + +/* DWT Control Register Definitions */ +#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */ +#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ + +#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */ +#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ + +#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */ +#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ + +#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */ +#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ + +#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */ +#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ + +#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */ +#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ + +#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */ +#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ + +#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */ +#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ + +#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */ +#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ + +#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */ +#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ + +#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */ +#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ + +#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */ +#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ + +#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */ +#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ + +#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */ +#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ + +#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */ +#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ + +#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */ +#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ + +#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */ +#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ + +#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */ +#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */ + +/* DWT CPI Count Register Definitions */ +#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */ +#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */ + +/* DWT Exception Overhead Count Register Definitions */ +#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */ +#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */ + +/* DWT Sleep Count Register Definitions */ +#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */ +#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ + +/* DWT LSU Count Register Definitions */ +#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */ +#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */ + +/* DWT Folded-instruction Count Register Definitions */ +#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */ +#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */ + +/* DWT Comparator Mask Register Definitions */ +#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */ +#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */ + +/* DWT Comparator Function Register Definitions */ +#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */ +#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ + +#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */ +#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ + +#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */ +#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ + +#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */ +#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ + +#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */ +#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ + +#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */ +#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ + +#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */ +#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ + +#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */ +#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ + +#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */ +#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */ + +/*@}*/ /* end of group CMSIS_DWT */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_TPI Trace Port Interface (TPI) + \brief Type definitions for the Trace Port Interface (TPI) + @{ + */ + +/** \brief Structure type to access the Trace Port Interface Register (TPI). + */ +typedef struct +{ + __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ + __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ + uint32_t RESERVED0[2]; + __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ + uint32_t RESERVED1[55]; + __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ + uint32_t RESERVED2[131]; + __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ + __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ + __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ + uint32_t RESERVED3[759]; + __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */ + __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ + __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ + uint32_t RESERVED4[1]; + __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ + __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ + __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ + uint32_t RESERVED5[39]; + __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ + __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ + uint32_t RESERVED7[8]; + __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ + __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ +} TPI_Type; + +/* TPI Asynchronous Clock Prescaler Register Definitions */ +#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */ +#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */ + +/* TPI Selected Pin Protocol Register Definitions */ +#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */ +#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */ + +/* TPI Formatter and Flush Status Register Definitions */ +#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */ +#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ + +#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */ +#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ + +#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */ +#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ + +#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */ +#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */ + +/* TPI Formatter and Flush Control Register Definitions */ +#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */ +#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ + +#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */ +#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ + +/* TPI TRIGGER Register Definitions */ +#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */ +#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */ + +/* TPI Integration ETM Data Register Definitions (FIFO0) */ +#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */ +#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ + +#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */ +#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ + +#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */ +#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ + +#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */ +#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ + +#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */ +#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ + +#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */ +#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ + +#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */ +#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */ + +/* TPI ITATBCTR2 Register Definitions */ +#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */ +#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */ + +/* TPI Integration ITM Data Register Definitions (FIFO1) */ +#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */ +#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ + +#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */ +#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ + +#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */ +#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ + +#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */ +#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ + +#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */ +#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ + +#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */ +#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ + +#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */ +#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */ + +/* TPI ITATBCTR0 Register Definitions */ +#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */ +#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */ + +/* TPI Integration Mode Control Register Definitions */ +#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */ +#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */ + +/* TPI DEVID Register Definitions */ +#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */ +#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ + +#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */ +#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ + +#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */ +#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ + +#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */ +#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ + +#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */ +#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ + +#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */ +#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */ + +/* TPI DEVTYPE Register Definitions */ +#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */ +#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */ + +#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */ +#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ + +/*@}*/ /* end of group CMSIS_TPI */ + + +#if (__MPU_PRESENT == 1) +/** \ingroup CMSIS_core_register + \defgroup CMSIS_MPU Memory Protection Unit (MPU) + \brief Type definitions for the Memory Protection Unit (MPU) + @{ + */ + +/** \brief Structure type to access the Memory Protection Unit (MPU). + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */ +#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@} end of group CMSIS_MPU */ +#endif + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) + \brief Type definitions for the Core Debug Registers + @{ + */ + +/** \brief Structure type to access the Core Debug Register (CoreDebug). + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ + +/*@} end of group CMSIS_CoreDebug */ + + +/** \ingroup CMSIS_core_register + \defgroup CMSIS_core_base Core Definitions + \brief Definitions for base addresses, unions, and structures. + @{ + */ + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ +#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ +#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ +#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ +#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ +#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ +#endif + +/*@} */ + + + +/******************************************************************************* + * Hardware Abstraction Layer + Core Function Interface contains: + - Core NVIC Functions + - Core SysTick Functions + - Core Debug Functions + - Core Register Access Functions + ******************************************************************************/ +/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference +*/ + + + +/* ########################## NVIC functions #################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_NVICFunctions NVIC Functions + \brief Functions that manage interrupts and exceptions via the NVIC. + @{ + */ + +/** \brief Set Priority Grouping + + The function sets the priority grouping field using the required unlock sequence. + The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. + Only values from 0..7 are used. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. + + \param [in] PriorityGroup Priority grouping field. + */ +__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + + +/** \brief Get Priority Grouping + + The function reads the priority grouping field from the NVIC Interrupt Controller. + + \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). + */ +__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + + +/** \brief Enable External Interrupt + + The function enables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ +} + + +/** \brief Disable External Interrupt + + The function disables a device-specific interrupt in the NVIC interrupt controller. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + + +/** \brief Get Pending Interrupt + + The function reads the pending register in the NVIC and returns the pending bit + for the specified interrupt. + + \param [in] IRQn Interrupt number. + + \return 0 Interrupt status is not pending. + \return 1 Interrupt status is pending. + */ +__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + + +/** \brief Set Pending Interrupt + + The function sets the pending bit of an external interrupt. + + \param [in] IRQn Interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + + +/** \brief Clear Pending Interrupt + + The function clears the pending bit of an external interrupt. + + \param [in] IRQn External interrupt number. Value cannot be negative. + */ +__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + + +/** \brief Get Active Interrupt + + The function reads the active register in NVIC and returns the active bit. + + \param [in] IRQn Interrupt number. + + \return 0 Interrupt status is not active. + \return 1 Interrupt status is active. + */ +__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + + +/** \brief Set Interrupt Priority + + The function sets the priority of an interrupt. + + \note The priority cannot be set for every core interrupt. + + \param [in] IRQn Interrupt number. + \param [in] priority Priority to set. + */ +__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + + +/** \brief Get Interrupt Priority + + The function reads the priority of an interrupt. The interrupt + number can be positive to specify an external (device specific) + interrupt, or negative to specify an internal (core) interrupt. + + + \param [in] IRQn Interrupt number. + \return Interrupt Priority. Value is aligned automatically to the implemented + priority bits of the microcontroller. + */ +__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** \brief Encode Priority + + The function encodes the priority for an interrupt with the given priority group, + preemptive priority value, and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set. + + \param [in] PriorityGroup Used priority group. + \param [in] PreemptPriority Preemptive priority value (starting from 0). + \param [in] SubPriority Subpriority value (starting from 0). + \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). + */ +__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** \brief Decode Priority + + The function decodes an interrupt priority value with a given priority group to + preemptive priority value and subpriority value. + In case of a conflict between priority grouping and available + priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + + \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). + \param [in] PriorityGroup Used priority group. + \param [out] pPreemptPriority Preemptive priority value (starting from 0). + \param [out] pSubPriority Subpriority value (starting from 0). + */ +__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + +/** \brief System Reset + + The function initiates a system reset request to reset the MCU. + */ +__STATIC_INLINE void NVIC_SystemReset(void) +{ + __DSB(); /* Ensure all outstanding memory accesses included + buffered write are completed before reset */ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@} end of CMSIS_Core_NVICFunctions */ + + + +/* ################################## SysTick function ############################################ */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_SysTickFunctions SysTick Functions + \brief Functions that configure the System. + @{ + */ + +#if (__Vendor_SysTickConfig == 0) + +/** \brief System Tick Configuration + + The function initializes the System Timer and its interrupt, and starts the System Tick Timer. + Counter is in free running mode to generate periodic interrupts. + + \param [in] ticks Number of ticks between two interrupts. + + \return 0 Function succeeded. + \return 1 Function failed. + + \note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the + function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b> + must contain a vendor-specific implementation of this function. + + */ +__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + +/*@} end of CMSIS_Core_SysTickFunctions */ + + + +/* ##################################### Debug In/Output function ########################################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_core_DebugFunctions ITM Functions + \brief Functions that access the ITM debug interface. + @{ + */ + +extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ + + +/** \brief ITM Send Character + + The function transmits a character via the ITM channel 0, and + \li Just returns when no debugger is connected that has booked the output. + \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. + + \param [in] ch Character to transmit. + + \returns Character to transmit. + */ +__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** \brief ITM Receive Character + + The function inputs a character via the external variable \ref ITM_RxBuffer. + + \return Received character. + \return -1 No character pending. + */ +__STATIC_INLINE int32_t ITM_ReceiveChar (void) { + int32_t ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** \brief ITM Check Character + + The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. + + \return 0 No character available. + \return 1 Character available. + */ +__STATIC_INLINE int32_t ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@} end of CMSIS_core_DebugFunctions */ + +#endif /* __CORE_CM3_H_DEPENDANT */ + +#endif /* __CMSIS_GENERIC */ + +#ifdef __cplusplus +} +#endif
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/core_cmFunc.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/core_cmFunc.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,609 @@ +/**************************************************************************//** + * @file core_cmFunc.h + * @brief CMSIS Cortex-M Core Function Access Header File + * @version V3.00 + * @date 09. December 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMFUNC_H +#define __CORE_CMFUNC_H + + +/* ########################### Core Function Access ########################### */ +/** \ingroup CMSIS_Core_FunctionInterface + \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions + @{ + */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +static __INLINE uint32_t __get_IPSR(void) +{ + register uint32_t __regIPSR __ASM("ipsr"); + return(__regIPSR); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +static __INLINE uint32_t __get_APSR(void) +{ + register uint32_t __regAPSR __ASM("apsr"); + return(__regAPSR); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +static __INLINE uint32_t __get_xPSR(void) +{ + register uint32_t __regXPSR __ASM("xpsr"); + return(__regXPSR); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + return(__regProcessStackPointer); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + register uint32_t __regProcessStackPointer __ASM("psp"); + __regProcessStackPointer = topOfProcStack; +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + return(__regMainStackPointer); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + register uint32_t __regMainStackPointer __ASM("msp"); + __regMainStackPointer = topOfMainStack; +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __enable_fault_irq __enable_fiq + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +#define __disable_fault_irq __disable_fiq + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & (uint32_t)1); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + return(__regfpscr); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + register uint32_t __regfpscr __ASM("fpscr"); + __regfpscr = (fpscr); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include <cmsis_iar.h> + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief Enable IRQ Interrupts + + This function enables IRQ interrupts by clearing the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_irq(void) +{ + __ASM volatile ("cpsie i"); +} + + +/** \brief Disable IRQ Interrupts + + This function disables IRQ interrupts by setting the I-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_irq(void) +{ + __ASM volatile ("cpsid i"); +} + + +/** \brief Get Control Register + + This function returns the content of the Control Register. + + \return Control Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_CONTROL(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + + +/** \brief Set Control Register + + This function writes the given value to the Control Register. + + \param [in] control Control Register value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** \brief Get IPSR Register + + This function returns the content of the IPSR Register. + + \return IPSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_IPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get APSR Register + + This function returns the content of the APSR Register. + + \return APSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_APSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, apsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get xPSR Register + + This function returns the content of the xPSR Register. + + \return xPSR Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_xPSR(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); + return(result); +} + + +/** \brief Get Process Stack Pointer + + This function returns the current value of the Process Stack Pointer (PSP). + + \return PSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, psp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Process Stack Pointer + + This function assigns the given value to the Process Stack Pointer (PSP). + + \param [in] topOfProcStack Process Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); +} + + +/** \brief Get Main Stack Pointer + + This function returns the current value of the Main Stack Pointer (MSP). + + \return MSP Register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_MSP(void) +{ + register uint32_t result; + + __ASM volatile ("MRS %0, msp\n" : "=r" (result) ); + return(result); +} + + +/** \brief Set Main Stack Pointer + + This function assigns the given value to the Main Stack Pointer (MSP). + + \param [in] topOfMainStack Main Stack Pointer value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); +} + + +/** \brief Get Priority Mask + + This function returns the current state of the priority mask bit from the Priority Mask Register. + + \return Priority Mask value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_PRIMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Priority Mask + + This function assigns the given value to the Priority Mask Register. + + \param [in] priMask Priority Mask + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Enable FIQ + + This function enables FIQ interrupts by clearing the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __enable_fault_irq(void) +{ + __ASM volatile ("cpsie f"); +} + + +/** \brief Disable FIQ + + This function disables FIQ interrupts by setting the F-bit in the CPSR. + Can only be executed in Privileged modes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __disable_fault_irq(void) +{ + __ASM volatile ("cpsid f"); +} + + +/** \brief Get Base Priority + + This function returns the current value of the Base Priority register. + + \return Base Priority register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_BASEPRI(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + + +/** \brief Set Base Priority + + This function assigns the given value to the Base Priority register. + + \param [in] basePri Base Priority value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + + +/** \brief Get Fault Mask + + This function returns the current value of the Fault Mask register. + + \return Fault Mask register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FAULTMASK(void) +{ + uint32_t result; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + + +/** \brief Set Fault Mask + + This function assigns the given value to the Fault Mask register. + + \param [in] faultMask Fault Mask value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + +#if (__CORTEX_M == 0x04) + +/** \brief Get FPSCR + + This function returns the current value of the Floating Point Status/Control register. + + \return Floating Point Status/Control register value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __get_FPSCR(void) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + uint32_t result; + + __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + return(result); +#else + return(0); +#endif +} + + +/** \brief Set FPSCR + + This function assigns the given value to the Floating Point Status/Control register. + + \param [in] fpscr Floating Point Status/Control value to set + */ +__attribute__( ( always_inline ) ) static __INLINE void __set_FPSCR(uint32_t fpscr) +{ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); +#endif +} + +#endif /* (__CORTEX_M == 0x04) */ + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@} end of CMSIS_Core_RegAccFunctions */ + + +#endif /* __CORE_CMFUNC_H */
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/core_cmInstr.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/core_cmInstr.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,585 @@ +/**************************************************************************//** + * @file core_cmInstr.h + * @brief CMSIS Cortex-M Core Instruction Access Header File + * @version V3.00 + * @date 09. December 2011 + * + * @note + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CORE_CMINSTR_H +#define __CORE_CMINSTR_H + + +/* ########################## Core Instruction Access ######################### */ +/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface + Access to dedicated instructions + @{ +*/ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#if (__ARMCC_VERSION < 400677) + #error "Please use ARM Compiler Toolchain V4.0.677 or later!" +#endif + + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +#define __NOP __nop + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +#define __WFI __wfi + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +#define __WFE __wfe + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +#define __SEV __sev + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +#define __ISB() __isb(0xF) + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +#define __DSB() __dsb(0xF) + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +#define __DMB() __dmb(0xF) + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __REV __rev + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +static __attribute__((section(".rev16_text"))) __INLINE __ASM uint32_t __REV16(uint32_t value) +{ + rev16 r0, r0 + bx lr +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +static __attribute__((section(".revsh_text"))) __INLINE __ASM int32_t __REVSH(int32_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +#define __RBIT __rbit + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXB(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXH(value, ptr) __strex(value, ptr) + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +#define __STREXW(value, ptr) __strex(value, ptr) + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +#define __CLREX __clrex + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT __ssat + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT __usat + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +#define __CLZ __clz + +#endif /* (__CORTEX_M >= 0x03) */ + + + +#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#include <cmsis_iar.h> + + +#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** \brief No Operation + + No Operation does nothing. This instruction can be used for code alignment purposes. + */ +__attribute__( ( always_inline ) ) static __INLINE void __NOP(void) +{ + __ASM volatile ("nop"); +} + + +/** \brief Wait For Interrupt + + Wait For Interrupt is a hint instruction that suspends execution + until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFI(void) +{ + __ASM volatile ("wfi"); +} + + +/** \brief Wait For Event + + Wait For Event is a hint instruction that permits the processor to enter + a low-power state until one of a number of events occurs. + */ +__attribute__( ( always_inline ) ) static __INLINE void __WFE(void) +{ + __ASM volatile ("wfe"); +} + + +/** \brief Send Event + + Send Event is a hint instruction. It causes an event to be signaled to the CPU. + */ +__attribute__( ( always_inline ) ) static __INLINE void __SEV(void) +{ + __ASM volatile ("sev"); +} + + +/** \brief Instruction Synchronization Barrier + + Instruction Synchronization Barrier flushes the pipeline in the processor, + so that all instructions following the ISB are fetched from cache or + memory, after the instruction has been completed. + */ +__attribute__( ( always_inline ) ) static __INLINE void __ISB(void) +{ + __ASM volatile ("isb"); +} + + +/** \brief Data Synchronization Barrier + + This function acts as a special kind of Data Memory Barrier. + It completes when all explicit memory accesses before this instruction complete. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DSB(void) +{ + __ASM volatile ("dsb"); +} + + +/** \brief Data Memory Barrier + + This function ensures the apparent order of the explicit memory operations before + and after the instruction, without ensuring their completion. + */ +__attribute__( ( always_inline ) ) static __INLINE void __DMB(void) +{ + __ASM volatile ("dmb"); +} + + +/** \brief Reverse byte order (32 bit) + + This function reverses the byte order in integer value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order (16 bit) + + This function reverses the byte order in two unsigned short values. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __REV16(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief Reverse byte order in signed short value + + This function reverses the byte order in a signed short value with sign extension to integer. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE int32_t __REVSH(int32_t value) +{ + uint32_t result; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +#if (__CORTEX_M >= 0x03) + +/** \brief Reverse bit order of value + + This function reverses the bit order of the given value. + + \param [in] value Value to reverse + \return Reversed value + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __RBIT(uint32_t value) +{ + uint32_t result; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + + +/** \brief LDR Exclusive (8 bit) + + This function performs a exclusive LDR command for 8 bit value. + + \param [in] ptr Pointer to data + \return value of type uint8_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __LDREXB(volatile uint8_t *addr) +{ + uint8_t result; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (16 bit) + + This function performs a exclusive LDR command for 16 bit values. + + \param [in] ptr Pointer to data + \return value of type uint16_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint16_t __LDREXH(volatile uint16_t *addr) +{ + uint16_t result; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief LDR Exclusive (32 bit) + + This function performs a exclusive LDR command for 32 bit values. + + \param [in] ptr Pointer to data + \return value of type uint32_t at (*ptr) + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __LDREXW(volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + + +/** \brief STR Exclusive (8 bit) + + This function performs a exclusive STR command for 8 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (16 bit) + + This function performs a exclusive STR command for 16 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) +{ + uint32_t result; + + __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief STR Exclusive (32 bit) + + This function performs a exclusive STR command for 32 bit values. + + \param [in] value Value to store + \param [in] ptr Pointer to location + \return 0 Function succeeded + \return 1 Function failed + */ +__attribute__( ( always_inline ) ) static __INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) +{ + uint32_t result; + + __ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +/** \brief Remove the exclusive lock + + This function removes the exclusive lock which is created by LDREX. + + */ +__attribute__( ( always_inline ) ) static __INLINE void __CLREX(void) +{ + __ASM volatile ("clrex"); +} + + +/** \brief Signed Saturate + + This function saturates a signed value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (1..32) + \return Saturated value + */ +#define __SSAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Unsigned Saturate + + This function saturates an unsigned value. + + \param [in] value Value to be saturated + \param [in] sat Bit position to saturate to (0..31) + \return Saturated value + */ +#define __USAT(ARG1,ARG2) \ +({ \ + uint32_t __RES, __ARG1 = (ARG1); \ + __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ + __RES; \ + }) + + +/** \brief Count leading zeros + + This function counts the number of leading zeros of a data value. + + \param [in] value Value to count the leading zeros + \return number of leading zeros in value + */ +__attribute__( ( always_inline ) ) static __INLINE uint8_t __CLZ(uint32_t value) +{ + uint8_t result; + + __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +#endif /* (__CORTEX_M >= 0x03) */ + + + + +#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all intrinsics, + * Including the CMSIS ones. + */ + +#endif + +/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ + +#endif /* __CORE_CMINSTR_H */
diff -r 000000000000 -r 80df663dd15e mbed/LPC1768/system_LPC17xx.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LPC1768/system_LPC17xx.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,60 @@ +/****************************************************************************** + * @file: system_LPC17xx.h + * @purpose: CMSIS Cortex-M3 Device Peripheral Access Layer Header File + * for the NXP LPC17xx Device Series + * @version: V1.02 + * @date: 27. July 2009 + *---------------------------------------------------------------------------- + * + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * ARM Limited (ARM) is supplying this software for use with Cortex-M3 + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + + +#ifndef __SYSTEM_LPC17xx_H +#define __SYSTEM_LPC17xx_H + +#ifdef __cplusplus + extern "C" { +#endif + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + + +/** + * Initialize the system + * + * @param none + * @return none + * + * @brief Setup the microcontroller system. + * Initialize the System and update the SystemCoreClock variable. + */ +extern void SystemInit (void); + +/** + * Update SystemCoreClock variable + * + * @param none + * @return none + * + * @brief Updates the SystemCoreClock with current core Clock + * retrieved from cpu registers. + */ +extern void SystemCoreClockUpdate (void); + +#ifdef __cplusplus +} +#endif + +#endif /* __SYSTEM_LPC17xx_H */
diff -r 000000000000 -r 80df663dd15e mbed/LocalFileSystem.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/LocalFileSystem.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,86 @@ +/* mbed Microcontroller Library - LocalFileSystem + * Copyright (c) 2008-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_LOCALFILESYSTEM_H +#define MBED_LOCALFILESYSTEM_H + +#include "FileSystemLike.h" + +namespace mbed { + +FILEHANDLE local_file_open(const char* name, int flags); + +class LocalFileHandle : public FileHandle { + +public: + LocalFileHandle(FILEHANDLE fh); + + virtual int close(); + + virtual ssize_t write(const void *buffer, size_t length); + + virtual ssize_t read(void *buffer, size_t length); + + virtual int isatty(); + + virtual off_t lseek(off_t position, int whence); + + virtual int fsync(); + + virtual off_t flen(); + +protected: + FILEHANDLE _fh; + int pos; +}; + +/* Class: LocalFileSystem + * A filesystem for accessing the local mbed Microcontroller USB disk drive + * + * This allows programs to read and write files on the same disk drive that is used to program the + * mbed Microcontroller. Once created, the standard C file access functions are used to open, + * read and write files. + * + * Example: + * > #include "mbed.h" + * > + * > LocalFileSystem local("local"); // Create the local filesystem under the name "local" + * > + * > int main() { + * > FILE *fp = fopen("/local/out.txt", "w"); // Open "out.txt" on the local file system for writing + * > fprintf(fp, "Hello World!"); + * > fclose(fp); + * > remove("/local/out.txt"); // Removes the file "out.txt" from the local file system + * > + * > DIR *d = opendir("/local"); // Opens the root directory of the local file system + * > struct dirent *p; + * > while((p = readdir(d)) != NULL) { // Print the names of the files in the local file system + * > printf("%s\n", p->d_name); // to stdout. + * > } + * > closedir(d); + * > } + * + * Implementation Notes: + * If the microcontroller program makes an access to the local drive, it will be marked as "removed" + * on the Host computer. This means it is no longer accessible from the Host Computer. + * + * The drive will only re-appear when the microcontroller program exists. Note that if the program does + * not exit, you will need to hold down reset on the mbed Microcontroller to be able to see the drive again! + */ +class LocalFileSystem : public FileSystemLike { + +public: + + LocalFileSystem(const char* n) : FileSystemLike(n) { + + } + + virtual FileHandle *open(const char* name, int flags); + virtual int remove(const char *filename); + virtual DirHandle *opendir(const char *name); +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PeripheralNames.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PeripheralNames.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,146 @@ +/* mbed Microcontroller Library - PeripheralNames + * Copyright (C) 2008-2011 ARM Limited. All rights reserved. + * + * Provides the mappings for peripherals + */ + +#ifndef MBED_PERIPHERALNAMES_H +#define MBED_PERIPHERALNAMES_H + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + +enum UARTName { + UART_0 = (int)LPC_UART0_BASE + , UART_1 = (int)LPC_UART1_BASE + , UART_2 = (int)LPC_UART2_BASE + , UART_3 = (int)LPC_UART3_BASE +}; +typedef enum UARTName UARTName; + +enum ADCName { + ADC0_0 = 0 + , ADC0_1 + , ADC0_2 + , ADC0_3 + , ADC0_4 + , ADC0_5 + , ADC0_6 + , ADC0_7 +}; +typedef enum ADCName ADCName; + +enum DACName { + DAC_0 = 0 +}; +typedef enum DACName DACName; + +enum SPIName { + SPI_0 = (int)LPC_SSP0_BASE + , SPI_1 = (int)LPC_SSP1_BASE +}; +typedef enum SPIName SPIName; + +enum I2CName { + I2C_0 = (int)LPC_I2C0_BASE + , I2C_1 = (int)LPC_I2C1_BASE + , I2C_2 = (int)LPC_I2C2_BASE +}; +typedef enum I2CName I2CName; + +enum PWMName { + PWM_1 = 1 + , PWM_2 + , PWM_3 + , PWM_4 + , PWM_5 + , PWM_6 +}; +typedef enum PWMName PWMName; + +enum TimerName { + TIMER_0 = (int)LPC_TIM0_BASE + , TIMER_1 = (int)LPC_TIM1_BASE + , TIMER_2 = (int)LPC_TIM2_BASE + , TIMER_3 = (int)LPC_TIM3_BASE +}; +typedef enum TimerName TimerName; + +enum CANName { + CAN_1 = (int)LPC_CAN1_BASE, + CAN_2 = (int)LPC_CAN2_BASE +}; +typedef enum CANName CANName; + +#define US_TICKER_TIMER TIMER_3 +#define US_TICKER_TIMER_IRQn TIMER3_IRQn + +#elif defined(TARGET_LPC11U24) + +enum UARTName { + UART_0 = (int)LPC_USART_BASE +}; +typedef enum UARTName UARTName; + +enum I2CName { + I2C_0 = (int)LPC_I2C_BASE +}; +typedef enum I2CName I2CName; + +enum TimerName { + TIMER_0 = (int)LPC_CT32B0_BASE + , TIMER_1 = (int)LPC_CT32B1_BASE +}; +typedef enum TimerName TimerName; + +enum ADCName { + ADC0_0 = 0 + , ADC0_1 + , ADC0_2 + , ADC0_3 + , ADC0_4 + , ADC0_5 + , ADC0_6 + , ADC0_7 +}; +typedef enum ADCName ADCName; + +enum SPIName { + SPI_0 = (int)LPC_SSP0_BASE + , SPI_1 = (int)LPC_SSP1_BASE +}; +typedef enum SPIName SPIName; + +#define US_TICKER_TIMER TIMER_1 +#define US_TICKER_TIMER_IRQn TIMER_32_1_IRQn + +typedef enum PWMName { + PWM_1 = 0 + , PWM_2 + , PWM_3 + , PWM_4 + , PWM_5 + , PWM_6 + , PWM_7 + , PWM_8 + , PWM_9 + , PWM_10 + , PWM_11 +} PWMName; + +#endif + +#define STDIO_UART_TX USBTX +#define STDIO_UART_RX USBRX +#define STDIO_UART UART_0 + +#ifdef __cplusplus +} +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PinNames.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PinNames.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,254 @@ +/* mbed Microcontroller Library - PinNames + * Copyright (C) 2008-2011 ARM Limited. All rights reserved. + * + * Provides the mapping of mbed DIP and LPC Pin Names + */ + +#ifndef MBED_PINNAMES_H +#define MBED_PINNAMES_H + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + +enum PinName { + + // LPC Pin Names + P0_0 = LPC_GPIO0_BASE, P0_1, P0_2, P0_3, P0_4, P0_5, P0_6, P0_7 + , P0_8, P0_9, P0_10, P0_11, P0_12, P0_13, P0_14, P0_15 + , P0_16, P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23 + , P0_24, P0_25, P0_26, P0_27, P0_28, P0_29, P0_30, P0_31 + , P1_0, P1_1, P1_2, P1_3, P1_4, P1_5, P1_6, P1_7 + , P1_8, P1_9, P1_10, P1_11, P1_12, P1_13, P1_14, P1_15 + , P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23 + , P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31 + , P2_0, P2_1, P2_2, P2_3, P2_4, P2_5, P2_6, P2_7 + , P2_8, P2_9, P2_10, P2_11, P2_12, P2_13, P2_14, P2_15 + , P2_16, P2_17, P2_18, P2_19, P2_20, P2_21, P2_22, P2_23 + , P2_24, P2_25, P2_26, P2_27, P2_28, P2_29, P2_30, P2_31 + , P3_0, P3_1, P3_2, P3_3, P3_4, P3_5, P3_6, P3_7 + , P3_8, P3_9, P3_10, P3_11, P3_12, P3_13, P3_14, P3_15 + , P3_16, P3_17, P3_18, P3_19, P3_20, P3_21, P3_22, P3_23 + , P3_24, P3_25, P3_26, P3_27, P3_28, P3_29, P3_30, P3_31 + , P4_0, P4_1, P4_2, P4_3, P4_4, P4_5, P4_6, P4_7 + , P4_8, P4_9, P4_10, P4_11, P4_12, P4_13, P4_14, P4_15 + , P4_16, P4_17, P4_18, P4_19, P4_20, P4_21, P4_22, P4_23 + , P4_24, P4_25, P4_26, P4_27, P4_28, P4_29, P4_30, P4_31 + + // mbed DIP Pin Names + , p5 = P0_9 + , p6 = P0_8 + , p7 = P0_7 + , p8 = P0_6 + , p9 = P0_0 + , p10 = P0_1 + , p11 = P0_18 + , p12 = P0_17 + , p13 = P0_15 + , p14 = P0_16 + , p15 = P0_23 + , p16 = P0_24 + , p17 = P0_25 + , p18 = P0_26 + , p19 = P1_30 + , p20 = P1_31 + , p21 = P2_5 + , p22 = P2_4 + , p23 = P2_3 + , p24 = P2_2 + , p25 = P2_1 + , p26 = P2_0 + , p27 = P0_11 + , p28 = P0_10 + , p29 = P0_5 + , p30 = P0_4 + + // Other mbed Pin Names +#ifdef MCB1700 + , LED1 = P1_28 + , LED2 = P1_29 + , LED3 = P1_31 + , LED4 = P2_2 +#else + , LED1 = P1_18 + , LED2 = P1_20 + , LED3 = P1_21 + , LED4 = P1_23 +#endif + , USBTX = P0_2 + , USBRX = P0_3 + + // Not connected + , NC = (int)0xFFFFFFFF + +}; +typedef enum PinName PinName; + +enum PinMode { + PullUp = 0 + , PullDown = 3 + , PullNone = 2 + , OpenDrain = 4 +}; +typedef enum PinMode PinMode; + +// version of PINCON_TypeDef using register arrays +typedef struct { + __IO uint32_t PINSEL[11]; + uint32_t RESERVED0[5]; + __IO uint32_t PINMODE[10]; +#ifndef TARGET_LPC2368 +// Open drain mode is not available on LPC2368 + __IO uint32_t PINMODE_OD[5]; +#endif +} PINCONARRAY_TypeDef; + +#define PINCONARRAY ((PINCONARRAY_TypeDef *)LPC_PINCON_BASE) + + +#elif defined(TARGET_LPC11U24) + +enum PinName { + + // LPC11U Pin Names + P0_0 = 0 + , P0_1 = 1 + , P0_2 = 2 + , P0_3 = 3 + , P0_4 = 4 + , P0_5 = 5 + , P0_6 = 6 + , P0_7 = 7 + , P0_8 = 8 + , P0_9 = 9 + , P0_10 = 10 + , P0_11 = 11 + , P0_12 = 12 + , P0_13 = 13 + , P0_14 = 14 + , P0_15 = 15 + , P0_16 = 16 + , P0_17 = 17 + , P0_18 = 18 + , P0_19 = 19 + , P0_20 = 20 + , P0_21 = 21 + , P0_22 = 22 + , P0_23 = 23 + , P0_24 = 24 + , P0_25 = 25 + , P0_26 = 26 + , P0_27 = 27 + + , P1_0 = 32 + , P1_1 = 33 + , P1_2 = 34 + , P1_3 = 35 + , P1_4 = 36 + , P1_5 = 37 + , P1_6 = 38 + , P1_7 = 39 + , P1_8 = 40 + , P1_9 = 41 + , P1_10 = 42 + , P1_11 = 43 + , P1_12 = 44 + , P1_13 = 45 + , P1_14 = 46 + , P1_15 = 47 + , P1_16 = 48 + , P1_17 = 49 + , P1_18 = 50 + , P1_19 = 51 + , P1_20 = 52 + , P1_21 = 53 + , P1_22 = 54 + , P1_23 = 55 + , P1_24 = 56 + , P1_25 = 57 + , P1_26 = 58 + , P1_27 = 59 + , P1_28 = 60 + , P1_29 = 61 + + , P1_31 = 63 + + // mbed DIP Pin Names + , p5 = P0_9 + , p6 = P0_8 + , p7 = P1_29 + , p8 = P0_2 + , p9 = P1_27 + , p10 = P1_26 + , p11 = P1_22 + , p12 = P1_21 + , p13 = P1_20 + , p14 = P1_23 + , p15 = P0_11 + , p16 = P0_12 + , p17 = P0_13 + , p18 = P0_14 + , p19 = P0_16 + , p20 = P0_22 + , p21 = P0_7 + , p22 = P0_17 + , p23 = P1_17 + , p24 = P1_18 + , p25 = P1_24 + , p26 = P1_25 + , p27 = P0_4 + , p28 = P0_5 + , p29 = P1_5 + , p30 = P1_2 + + , p33 = P0_3 + , p34 = P1_15 + , p35 = P0_20 + , p36 = P0_21 + + // Other mbed Pin Names + , LED1 = P1_8 + , LED2 = P1_9 + , LED3 = P1_10 + , LED4 = P1_11 + + , USBTX = P0_19 + , USBRX = P0_18 + + // Not connected + , NC = (int)0xFFFFFFFF + +}; +typedef enum PinName PinName; + +typedef enum { + CHANNEL0=FLEX_INT0_IRQn, + CHANNEL1=FLEX_INT1_IRQn, + CHANNEL2=FLEX_INT2_IRQn, + CHANNEL3=FLEX_INT3_IRQn, + CHANNEL4=FLEX_INT4_IRQn, + CHANNEL5=FLEX_INT5_IRQn, + CHANNEL6=FLEX_INT6_IRQn, + CHANNEL7=FLEX_INT7_IRQn +} Channel; + +enum PinMode { + PullUp = 2 + , PullDown = 1 + , PullNone = 0 + , Repeater = 3 + , OpenDrain = 4 +}; +typedef enum PinMode PinMode; +#endif + + +#ifdef __cplusplus +} +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PortIn.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PortIn.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,86 @@ +/* mbed Microcontroller Library - PortInOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PORTIN_H +#define MBED_PORTIN_H + +#include "device.h" + +#if DEVICE_PORTIN + +#include "PortNames.h" +#include "PinNames.h" + +namespace mbed { + +/* Class: PortIn + * A multiple pin digital input + * + * Example: + * > // Switch on an LED if any of mbed pins 21-26 is high + * > + * > #include "mbed.h" + * > + * > PortIn p(Port2, 0x0000003F); // p21-p26 + * > DigitalOut ind(LED4); + * > + * > int main() { + * > while(1) { + * > int pins = p.read(); + * > if(pins) { + * > ind = 1; + * > } else { + * > ind = 0; + * > } + * > } + * > } + */ +class PortIn { +public: + + /* Constructor: PortIn + * Create an PortIn, connected to the specified port + * + * Variables: + * port - Port to connect to (Port0-Port5) + * mask - A bitmask to identify which bits in the port should be included (0 - ignore) + */ + PortIn(PortName port, int mask = 0xFFFFFFFF); + + /* Function: read + * Read the value currently output on the port + * + * Variables: + * returns - An integer with each bit corresponding to associated port pin setting + */ + int read(); + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone, OpenDrain + */ + void mode(PinMode mode); + + /* Function: operator int() + * A shorthand for <read> + */ + operator int() { + return read(); + } + +private: +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#endif + PortName _port; + uint32_t _mask; +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PortInOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PortInOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,98 @@ +/* mbed Microcontroller Library - PortInOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PORTINOUT_H +#define MBED_PORTINOUT_H + +#include "device.h" + +#if DEVICE_PORTINOUT + +#include "PortNames.h" +#include "PinNames.h" + +namespace mbed { + +/* Class: PortInOut + * A multiple pin digital in/out used to set/read multiple bi-directional pins + */ +class PortInOut { +public: + + /* Constructor: PortInOut + * Create an PortInOut, connected to the specified port + * + * Variables: + * port - Port to connect to (Port0-Port5) + * mask - A bitmask to identify which bits in the port should be included (0 - ignore) + */ + PortInOut(PortName port, int mask = 0xFFFFFFFF); + + /* Function: write + * Write the value to the output port + * + * Variables: + * value - An integer specifying a bit to write for every corresponding port pin + */ + void write(int value); + + /* Function: read + * Read the value currently output on the port + * + * Variables: + * returns - An integer with each bit corresponding to associated port pin setting + */ + int read(); + + /* Function: output + * Set as an output + */ + void output(); + + /* Function: input + * Set as an input + */ + void input(); + + /* Function: mode + * Set the input pin mode + * + * Variables: + * mode - PullUp, PullDown, PullNone, OpenDrain + */ + void mode(PinMode mode); + + /* Function: operator= + * A shorthand for <write> + */ + PortInOut& operator= (int value) { + write(value); + return *this; + } + + PortInOut& operator= (PortInOut& rhs) { + write(rhs.read()); + return *this; + } + + /* Function: operator int() + * A shorthand for <read> + */ + operator int() { + return read(); + } + +private: +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#endif + PortName _port; + uint32_t _mask; +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PortNames.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PortNames.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,38 @@ +/* mbed Microcontroller Library - PortName + * Copyright (c) 2010-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PORTNAMES_H +#define MBED_PORTNAMES_H + +#ifdef __cplusplus +extern "C" { +#endif + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + +enum PortName { + Port0 = 0 + , Port1 = 1 + , Port2 = 2 + , Port3 = 3 + , Port4 = 4 +}; +typedef enum PortName PortName; + +#elif defined(TARGET_LPC11U24) + +enum PortName { + Port0 = 0 + , Port1 = 1 +}; +typedef enum PortName PortName; + + +#endif + +#ifdef __cplusplus +} +#endif +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/PortOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PortOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,101 @@ +/* mbed Microcontroller Library - PortOut + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PORTOUT_H +#define MBED_PORTOUT_H + +#include "device.h" + +#if DEVICE_PORTOUT + +#include "platform.h" +#include "PinNames.h" +#include "Base.h" + +#include "PortNames.h" + +namespace mbed { +/* Class: PortOut + * A multiple pin digital out + * + * Example: + * > // Toggle all four LEDs + * > + * > #include "mbed.h" + * > + * > // LED1 = P1.18 LED2 = P1.20 LED3 = P1.21 LED4 = P1.23 + * > #define LED_MASK 0x00B40000 + * > + * > PortOut ledport(Port1, LED_MASK); + * > + * > int main() { + * > while(1) { + * > ledport = LED_MASK; + * > wait(1); + * > ledport = 0; + * > wait(1); + * > } + * > } + */ +class PortOut { +public: + + /* Constructor: PortOut + * Create an PortOut, connected to the specified port + * + * Variables: + * port - Port to connect to (Port0-Port5) + * mask - A bitmask to identify which bits in the port should be included (0 - ignore) + */ + PortOut(PortName port, int mask = 0xFFFFFFFF); + + /* Function: write + * Write the value to the output port + * + * Variables: + * value - An integer specifying a bit to write for every corresponding PortOut pin + */ + void write(int value); + + /* Function: read + * Read the value currently output on the port + * + * Variables: + * returns - An integer with each bit corresponding to associated PortOut pin setting + */ + int read(); + + /* Function: operator= + * A shorthand for <write> + */ + PortOut& operator= (int value) { + write(value); + return *this; + } + + PortOut& operator= (PortOut& rhs) { + write(rhs.read()); + return *this; + } + + /* Function: operator int() + * A shorthand for <read> + */ + operator int() { + return read(); + } + +private: +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + LPC_GPIO_TypeDef *_gpio; +#endif + PortName _port; + uint32_t _mask; +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/PwmOut.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/PwmOut.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,148 @@ +/* mbed Microcontroller Library - PwmOut + * Copyright (c) 2007-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PWMOUT_H +#define MBED_PWMOUT_H + +#include "device.h" + +#if DEVICE_PWMOUT + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: PwmOut + * A pulse-width modulation digital output + * + * Example + * > // Fade a led on. + * > #include "mbed.h" + * > + * > PwmOut led(LED1); + * > + * > int main() { + * > while(1) { + * > led = led + 0.01; + * > wait(0.2); + * > if(led == 1.0) { + * > led = 0; + * > } + * > } + * > } + * + * Note that on the LPC1768 and LPC2368, the PWMs all share the same + * period - if you change the period for one, you change it for all. + * Although routines that change the period maintain the duty cycle + * for its PWM, all other PWMs will require their duty cycle to be + * refreshed. + */ +class PwmOut : public Base { + +public: + + /* Constructor: PwmOut + * Create a PwmOut connected to the specified pin + * + * Variables: + * pin - PwmOut pin to connect to + */ + PwmOut(PinName pin, const char *name = NULL); + + /* Function: write + * Set the ouput duty-cycle, specified as a percentage (float) + * + * Variables: + * value - A floating-point value representing the output duty-cycle, + * specified as a percentage. The value should lie between + * 0.0f (representing on 0%) and 1.0f (representing on 100%). + * Values outside this range will be saturated to 0.0f or 1.0f. + */ + void write(float value); + + /* Function: read + * Return the current output duty-cycle setting, measured as a percentage (float) + * + * Variables: + * returns - A floating-point value representing the current duty-cycle being output on the pin, + * measured as a percentage. The returned value will lie between + * 0.0f (representing on 0%) and 1.0f (representing on 100%). + * + * Note: + * This value may not match exactly the value set by a previous <write>. + */ + float read(); + + /* Function: period + * Set the PWM period, specified in seconds (float), keeping the + * duty cycle the same. + * + * Note: + * The resolution is currently in microseconds; periods smaller than this + * will be set to zero. + */ + void period(float seconds); + + /* Function: period_ms + * Set the PWM period, specified in milli-seconds (int), keeping the + * duty cycle the same. + */ + void period_ms(int ms); + + /* Function: period_us + * Set the PWM period, specified in micro-seconds (int), keeping the + * duty cycle the same. + */ + void period_us(int us); + + /* Function: pulsewidth + * Set the PWM pulsewidth, specified in seconds (float), keeping the + * period the same. + */ + void pulsewidth(float seconds); + + /* Function: pulsewidth_ms + * Set the PWM pulsewidth, specified in milli-seconds (int), keeping + * the period the same. + */ + void pulsewidth_ms(int ms); + + /* Function: pulsewidth_us + * Set the PWM pulsewidth, specified in micro-seconds (int), keeping + * the period the same. + */ + void pulsewidth_us(int us); + +#ifdef MBED_OPERATORS + /* Function: operator= + * A operator shorthand for <write()> + */ + PwmOut& operator= (float value); + PwmOut& operator= (PwmOut& rhs); + + /* Function: operator float() + * An operator shorthand for <read()> + */ + operator float(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + PWMName _pwm; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/SPI.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/SPI.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,113 @@ +/* mbed Microcontroller Library - SPI + * Copyright (c) 2010-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_SPI_H +#define MBED_SPI_H + +#include "device.h" + +#if DEVICE_SPI + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: SPI + * A SPI Master, used for communicating with SPI slave devices + * + * The default format is set to 8-bits, mode 0, and a clock frequency of 1MHz + * + * Most SPI devices will also require Chip Select and Reset signals. These + * can be controlled using <DigitalOut> pins + * + * Example: + * > // Send a byte to a SPI slave, and record the response + * > + * > #include "mbed.h" + * > + * > SPI device(p5, p6, p7); // mosi, miso, sclk + * > + * > int main() { + * > int response = device.write(0xFF); + * > } + */ +class SPI : public Base { + +public: + + /* Constructor: SPI + * Create a SPI master connected to the specified pins + * + * Variables: + * mosi - SPI Master Out, Slave In pin + * miso - SPI Master In, Slave Out pin + * sclk - SPI Clock pin + * name - (optional) A string to identify the object + * + * Pin Options: + * (5, 6, 7) or (11, 12, 13) + * + * mosi or miso can be specfied as NC if not used + */ + SPI(PinName mosi, PinName miso, PinName sclk, const char *name = NULL); + + /* Function: format + * Configure the data transmission format + * + * Variables: + * bits - Number of bits per SPI frame (4 - 16) + * mode - Clock polarity and phase mode (0 - 3) + * + * > mode | POL PHA + * > -----+-------- + * > 0 | 0 0 + * > 1 | 0 1 + * > 2 | 1 0 + * > 3 | 1 1 + */ + void format(int bits, int mode = 0); + + /* Function: frequency + * Set the spi bus clock frequency + * + * Variables: + * hz - SCLK frequency in hz (default = 1MHz) + */ + void frequency(int hz = 1000000); + + /* Function: write + * Write to the SPI Slave and return the response + * + * Variables: + * value - Data to be sent to the SPI slave + * returns - Response from the SPI slave + */ + virtual int write(int value); + + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + SPIName _spi; + + void aquire(void); + static SPI *_owner; + int _bits; + int _mode; + int _hz; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/SPIHalfDuplex.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/SPIHalfDuplex.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,117 @@ +/* mbed Microcontroller Library - SPIHalfDuplex + * Copyright (c) 2010-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_SPIHALFDUPLEX_H +#define MBED_SPIHALFDUPLEX_H + +#include "device.h" + +#if DEVICE_SPI + +#include "SPI.h" + +namespace mbed { + +/* Class: SPIHalfDuplex + * A SPI half-duplex master, used for communicating with SPI slave devices + * over a shared data line. + * + * The default format is set to 8-bits for both master and slave, and a + * clock frequency of 1MHz + * + * Most SPI devies will also require Chip Select and Reset signals. These + * can be controlled using <DigitalOut> pins. + * + * Although this is for a shared data line, both MISO and MOSI are defined, + * and should be tied together externally to the mbed. This class handles + * the tri-stating of the MOSI pin. + * + * Example: + * > // Send a byte to a SPI half-duplex slave, and record the response + * > + * > #include "mbed.h" + * > + * > SPIHalfDuplex device(p5, p6, p7) // mosi, miso, sclk + * > + * > int main() { + * > int respone = device.write(0xAA); + * > } + */ + +class SPIHalfDuplex : public SPI { + +public: + + /* Constructor: SPIHalfDuplex + * Create a SPI half-duplex master connected to the specified pins + * + * Variables: + * mosi - SPI Master Out, Slave In pin + * miso - SPI Master In, Slave Out pin + * sclk - SPI Clock pin + * name - (optional) A string to identify the object + * + * Pin Options: + * (5, 6, 7) or (11, 12, 13) + * + * mosi or miso can be specfied as NC if not used + */ + SPIHalfDuplex(PinName mosi, PinName miso, PinName sclk, + const char *name = NULL); + +#if 0 // Inherited from SPI - documentation only + /* Function: format + * Configure the data transmission format + * + * Variables: + * bits - Number of bits per SPI frame (4 - 16) + * mode - Clock polarity and phase mode (0 - 3) + * + * > mode | POL PHA + * > -----+-------- + * > 0 | 0 0 + * > 1 | 0 1 + * > 2 | 1 0 + * > 3 | 1 1 + */ + void format(int bits, int mode = 0); + + /* Function: frequency + * Set the spi bus clock frequency + * + * Variables: + * hz - SCLK frequency in hz (default = 1MHz) + */ + void frequency(int hz = 1000000); +#endif + + /* Function: write + * Write to the SPI Slave and return the response + * + * Variables: + * value - Data to be sent to the SPI slave + * returns - Response from the SPI slave + */ + virtual int write(int value); + + /* Function: slave_format + * Set the number of databits expected from the slave, from 4-16 + * + * Variables: + * sbits - Number of expected bits in the slave response + */ + void slave_format(int sbits); + +protected: + PinName _mosi; + PinName _miso; + int _sbits; + +}; // End of class + +} // End of namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/SPISlave.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/SPISlave.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,127 @@ +/* mbed Microcontroller Library - SPISlave + * Copyright (c) 2010-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_SPISLAVE_H +#define MBED_SPISLAVE_H + +#include "device.h" + +#if DEVICE_SPISLAVE + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: SPISlave + * A SPI slave, used for communicating with a SPI Master device + * + * The default format is set to 8-bits, mode 0, and a clock frequency of 1MHz + * + * Example: + * > // Reply to a SPI master as slave + * > + * > #include "mbed.h" + * > + * > SPISlave device(p5, p6, p7, p8); // mosi, miso, sclk, ssel + * > + * > int main() { + * > device.reply(0x00); // Prime SPI with first reply + * > while(1) { + * > if(device.receive()) { + * > int v = device.read(); // Read byte from master + * > v = (v + 1) % 0x100; // Add one to it, modulo 256 + * > device.reply(v); // Make this the next reply + * > } + * > } + * > } + */ +class SPISlave : public Base { + +public: + + /* Constructor: SPI + * Create a SPI slave connected to the specified pins + * + * Variables: + * mosi - SPI Master Out, Slave In pin + * miso - SPI Master In, Slave Out pin + * sclk - SPI Clock pin + * ssel - SPI chip select pin + * name - (optional) A string to identify the object + * + * Pin Options: + * (5, 6, 7i, 8) or (11, 12, 13, 14) + * + * mosi or miso can be specfied as NC if not used + */ + SPISlave(PinName mosi, PinName miso, PinName sclk, PinName ssel, + const char *name = NULL); + + /* Function: format + * Configure the data transmission format + * + * Variables: + * bits - Number of bits per SPI frame (4 - 16) + * mode - Clock polarity and phase mode (0 - 3) + * + * > mode | POL PHA + * > -----+-------- + * > 0 | 0 0 + * > 1 | 0 1 + * > 2 | 1 0 + * > 3 | 1 1 + */ + void format(int bits, int mode = 0); + + /* Function: frequency + * Set the spi bus clock frequency + * + * Variables: + * hz - SCLK frequency in hz (default = 1MHz) + */ + void frequency(int hz = 1000000); + + /* Function: receive + * Polls the SPI to see if data has been received + * + * Variables: + * returns - zero if no data, 1 otherwise + */ + int receive(void); + + /* Function: read + * Retrieve data from receive buffer as slave + * + * Variables: + * returns - the data in the receive buffer + */ + int read(void); + + /* Function: reply + * Fill the transmission buffer with the value to be written out + * as slave on the next received message from the master. + * + * Variables: + * value - the data to be transmitted next + */ + void reply(int value); + +protected: + + SPIName _spi; + + int _bits; + int _mode; + int _hz; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/Serial.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Serial.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,189 @@ +/* mbed Microcontroller Library - Serial + * Copyright (c) 2007-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_SERIAL_H +#define MBED_SERIAL_H + +#include "device.h" + +#if DEVICE_SERIAL + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Stream.h" +#include "FunctionPointer.h" + +namespace mbed { + +/* Class: Serial + * A serial port (UART) for communication with other serial devices + * + * Can be used for Full Duplex communication, or Simplex by specifying + * one pin as NC (Not Connected) + * + * Example: + * > // Print "Hello World" to the PC + * > + * > #include "mbed.h" + * > + * > Serial pc(USBTX, USBRX); + * > + * > int main() { + * > pc.printf("Hello World\n"); + * > } + */ +class Serial : public Stream { + +public: + + /* Constructor: Serial + * Create a Serial port, connected to the specified transmit and receive pins + * + * Variables: + * tx - Transmit pin + * rx - Receive pin + * + * Note: Either tx or rx may be specified as NC if unused + */ + Serial(PinName tx, PinName rx, const char *name = NULL); + + /* Function: baud + * Set the baud rate of the serial port + * + * Variables: + * baudrate - The baudrate of the serial port (default = 9600). + */ + void baud(int baudrate); + + enum Parity { + None = 0 + , Odd + , Even + , Forced1 + , Forced0 + }; + + enum IrqType { + RxIrq = 0 + , TxIrq + }; + + /* Function: format + * Set the transmission format used by the Serial port + * + * Variables: + * bits - The number of bits in a word (5-8; default = 8) + * parity - The parity used (Serial::None, Serial::Odd, Serial::Even, Serial::Forced1, Serial::Forced0; default = Serial::None) + * stop - The number of stop bits (1 or 2; default = 1) + */ + void format(int bits = 8, Parity parity = Serial::None, int stop_bits = 1); + +#if 0 // Inhereted from Stream, for documentation only + + /* Function: putc + * Write a character + * + * Variables: + * c - The character to write to the serial port + */ + int putc(int c); + + /* Function: getc + * Read a character + * + * Reads a character from the serial port. This will block until + * a character is available. To see if a character is available, + * see <readable> + * + * Variables: + * returns - The character read from the serial port + */ + int getc(); + + /* Function: printf + * Write a formated string + * + * Variables: + * format - A printf-style format string, followed by the + * variables to use in formating the string. + */ + int printf(const char* format, ...); + + /* Function: scanf + * Read a formated string + * + * Variables: + * format - A scanf-style format string, + * followed by the pointers to variables to store the results. + */ + int scanf(const char* format, ...); + +#endif + + /* Function: readable + * Determine if there is a character available to read + * + * Variables: + * returns - 1 if there is a character available to read, else 0 + */ + int readable(); + + /* Function: writeable + * Determine if there is space available to write a character + * + * Variables: + * returns - 1 if there is space to write a character, else 0 + */ + int writeable(); + + /* Function: attach + * Attach a function to call whenever a serial interrupt is generated + * + * Variables: + * fptr - A pointer to a void function, or 0 to set as none + * type - Which serial interrupt to attach the member function to (Seriall::RxIrq for receive, TxIrq for transmit buffer empty) + */ + void attach(void (*fptr)(void), IrqType type = RxIrq); + + /* Function: attach + * Attach a member function to call whenever a serial interrupt is generated + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + * type - Which serial interrupt to attach the member function to (Seriall::RxIrq for receive, TxIrq for transmit buffer empty) + */ + template<typename T> + void attach(T* tptr, void (T::*mptr)(void), IrqType type = RxIrq) { + if((mptr != NULL) && (tptr != NULL)) { + _irq[type].attach(tptr, mptr); + setup_interrupt(type); + } + } + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + void setup_interrupt(IrqType type); + void remove_interrupt(IrqType type); + + virtual int _getc(); + virtual int _putc(int c); + + UARTName _uart; + FunctionPointer _irq[2]; + int _uidx; + +}; + +} // namespace mbed + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/SerialHalfDuplex.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/SerialHalfDuplex.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,188 @@ +/* mbed Microcontroller Library - SerialHalfDuplex + * Copyright (c) 2010-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_SERIALHALFDUPLEX_H +#define MBED_SERIALHALFDUPLEX_H + +#include "device.h" + +#if DEVICE_SERIAL + +#include "Serial.h" +#include "PinNames.h" +#include "PeripheralNames.h" + +namespace mbed { + +/* Class: SerialHalfDuplex + * A serial port (UART) for communication with other devices using + * Half-Duplex, allowing transmit and receive on a single + * shared transmit and receive line. Only one end should be transmitting + * at a time. + * + * Both the tx and rx pin should be defined, and wired together. + * This is in addition to them being wired to the other serial + * device to allow both read and write functions to operate. + * + * Example: + * > // Send a byte to a second HalfDuplex device, and read the response + * > + * > #include "mbed.h" + * > + * > // p9 and p10 should be wired together to form "a" + * > // p28 and p27 should be wired together to form "b" + * > // p9/p10 should be wired to p28/p27 as the Half Duplex connection + * > + * > SerialHalfDuplex a(p9, p10); + * > SerialHalfDuplex b(p28, p27); + * > + * > void b_rx() { // second device response + * > b.putc(b.getc() + 4); + * > } + * > + * > int main() { + * > b.attach(&b_rx); + * > for(int c = 'A'; c < 'Z'; c++) { + * > a.putc(c); + * > printf("sent [%c]\n", c); + * > wait(0.5); // b should respond + * > if(a.readable()) { + * > printf("received [%c]\n", a.getc()); + * > } + * > } + * > } + * + * For Simplex and Full-Duplex Serial communication, see <Serial> + */ +class SerialHalfDuplex : public Serial { + +public: + /* Constructor: SerialHalfDuplex + * Create a half-duplex serial port, connected to the specified transmit + * and receive pins. + * + * These pins should be wired together, as well as to the target device + * + * Variables: + * tx - Transmit pin + * rx - Receive pin + */ + SerialHalfDuplex(PinName tx, PinName rx, const char *name = NULL); + +#if 0 // Inherited from Serial class, for documentation + /* Function: baud + * Set the baud rate of the serial port + * + * Variables: + * baudrate - The baudrate of the serial port (default = 9600). + */ + void baud(int baudrate); + + enum Parity { + None = 0 + , Odd + , Even + , Forced1 + , Forced0 + }; + + /* Function: format + * Set the transmission format used by the Serial port + * + * Variables: + * bits - The number of bits in a word (5-8; default = 8) + * parity - The parity used (Serial::None, Serial::Odd, +Serial::Even, Serial::Forced1, Serial::Forced0; default = Serial::None) + * stop - The number of stop bits (1 or 2; default = 1) + */ + void format(int bits = 8, Parity parity = Serial::None, int stop_bits += 1); + + /* Function: putc + * Write a character + * + * Variables: + * c - The character to write to the serial port + */ + int putc(int c); + + /* Function: getc + * Read a character + * + * Read a character from the serial port. This call will block + * until a character is available. For testing if a character is + * available for reading, see <readable>. + * + * Variables: + * returns - The character read from the serial port + */ + int getc(); + + /* Function: printf + * Write a formated string + * + * Variables: + * format - A printf-style format string, followed by the + * variables to use in formating the string. + */ + int printf(const char* format, ...); + + /* Function: scanf + * Read a formated string + * + * Variables: + * format - A scanf-style format string, + * followed by the pointers to variables to store the results. + */ + int scanf(const char* format, ...); + + /* Function: readable + * Determine if there is a character available to read + * + * Variables: + * returns - 1 if there is a character available to read, else 0 + */ + int readable(); + + /* Function: writeable + * Determine if there is space available to write a character + * + * Variables: + * returns - 1 if there is space to write a character, else 0 + */ + int writeable(); + + /* Function: attach + * Attach a function to call whenever a serial interrupt is generated + * + * Variables: + * fptr - A pointer to a void function, or 0 to set as none + */ + void attach(void (*fptr)(void)); + + /* Function: attach + * Attach a member function to call whenever a serial interrupt is generated + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + */ + template<typename T> + void attach(T* tptr, void (T::*mptr)(void)); + +#endif + +protected: + PinName _txpin; + + virtual int _putc(int c); + virtual int _getc(void); + +}; // End class SerialHalfDuplex + +} // End namespace + +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/Stream.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Stream.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,66 @@ +/* mbed Microcontroller Library - Stream + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_STREAM_H +#define MBED_STREAM_H + +#include "FileLike.h" +#include "platform.h" +#include <cstdio> + +namespace mbed { + +class Stream : public FileLike { + +public: + + Stream(const char *name = NULL); + virtual ~Stream(); + + int putc(int c) { + fflush(_file); + return std::fputc(c, _file); + } + int puts(const char *s) { + fflush(_file); + return std::fputs(s, _file); + } + int getc() { + fflush(_file); + return std::fgetc(_file); + } + char *gets(char *s, int size) { + fflush(_file); + return std::fgets(s,size,_file);; + } + int printf(const char* format, ...); + int scanf(const char* format, ...); + + operator std::FILE*() { return _file; } + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); +#endif + +protected: + + virtual int close(); + virtual ssize_t write(const void* buffer, size_t length); + virtual ssize_t read(void* buffer, size_t length); + virtual off_t lseek(off_t offset, int whence); + virtual int isatty(); + virtual int fsync(); + virtual off_t flen(); + + virtual int _putc(int c) = 0; + virtual int _getc() = 0; + + std::FILE *_file; + +}; + +} // namespace mbed + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/Ticker.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Ticker.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,117 @@ +/* mbed Microcontroller Library - Ticker + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_TICKER_H +#define MBED_TICKER_H + +#include "TimerEvent.h" +#include "FunctionPointer.h" + +namespace mbed { + +/* Class: Ticker + * A Ticker is used to call a function at a recurring interval + * + * You can use as many seperate Ticker objects as you require. + * + * Example: + * > // Toggle the blinking led after 5 seconds + * > + * > #include "mbed.h" + * > + * > Ticker timer; + * > DigitalOut led1(LED1); + * > DigitalOut led2(LED2); + * > + * > int flip = 0; + * > + * > void attime() { + * > flip = !flip; + * > } + * > + * > int main() { + * > timer.attach(&attime, 5); + * > while(1) { + * > if(flip == 0) { + * > led1 = !led1; + * > } else { + * > led2 = !led2; + * > } + * > wait(0.2); + * > } + * > } + * + */ +class Ticker : public TimerEvent { + +public: + + /* Function: attach + * Attach a function to be called by the Ticker, specifiying the interval in seconds + * + * Variables: + * fptr - pointer to the function to be called + * t - the time between calls in seconds + */ + void attach(void (*fptr)(void), float t) { + attach_us(fptr, t * 1000000.0f); + } + + /* Function: attach + * Attach a member function to be called by the Ticker, specifiying the interval in seconds + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + * t - the time between calls in seconds + */ + template<typename T> + void attach(T* tptr, void (T::*mptr)(void), float t) { + attach_us(tptr, mptr, t * 1000000.0f); + } + + /* Function: attach_us + * Attach a function to be called by the Ticker, specifiying the interval in micro-seconds + * + * Variables: + * fptr - pointer to the function to be called + * t - the time between calls in micro-seconds + */ + void attach_us(void (*fptr)(void), unsigned int t) { + _function.attach(fptr); + setup(t); + } + + /* Function: attach_us + * Attach a member function to be called by the Ticker, specifiying the interval in micro-seconds + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + * t - the time between calls in micro-seconds + */ + template<typename T> + void attach_us(T* tptr, void (T::*mptr)(void), unsigned int t) { + _function.attach(tptr, mptr); + setup(t); + } + + /* Function: detach + * Detach the function + */ + void detach(); + +protected: + + void setup(unsigned int t); + virtual void handler(); + + unsigned int _delay; + FunctionPointer _function; + +}; + +} // namespace mbed + +#endif \ No newline at end of file
diff -r 000000000000 -r 80df663dd15e mbed/Timeout.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Timeout.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,108 @@ +/* mbed Microcontroller Library - Timeout + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_TIMEOUT_H +#define MBED_TIMEOUT_H + +#include "Ticker.h" + +namespace mbed { + +/* Class: Timeout + * A Timeout is used to call a function at a point in the future + * + * You can use as many seperate Timeout objects as you require. + * + * Example: + * > // Blink until timeout. + * > + * > #include "mbed.h" + * > + * > Timeout timeout; + * > DigitalOut led(LED1); + * > + * > int on = 1; + * > + * > void attimeout() { + * > on = 0; + * > } + * > + * > int main() { + * > timeout.attach(&attimeout, 5); + * > while(on) { + * > led = !led; + * > wait(0.2); + * > } + * > } + */ +class Timeout : public Ticker { + +#if 0 // For documentation + + /* Function: attach + * Attach a function to be called by the Timeout, specifiying the delay in seconds + * + * Variables: + * fptr - pointer to the function to be called + * t - the time before the call in seconds + */ + void attach(void (*fptr)(void), float t) { + attach_us(fptr, t * 1000000.0f); + } + + /* Function: attach + * Attach a member function to be called by the Timeout, specifiying the delay in seconds + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + * t - the time before the calls in seconds + */ + template<typename T> + void attach(T* tptr, void (T::*mptr)(void), float t) { + attach_us(tptr, mptr, t * 1000000.0f); + } + + /* Function: attach_us + * Attach a function to be called by the Timeout, specifiying the delay in micro-seconds + * + * Variables: + * fptr - pointer to the function to be called + * t - the time before the call in micro-seconds + */ + void attach_us(void (*fptr)(void), unsigned int t) { + _function.attach(fptr); + setup(t); + } + + /* Function: attach_us + * Attach a member function to be called by the Timeout, specifiying the delay in micro-seconds + * + * Variables: + * tptr - pointer to the object to call the member function on + * mptr - pointer to the member function to be called + * t - the time before the call in micro-seconds + */ + template<typename T> + void attach_us(T* tptr, void (T::*mptr)(void), unsigned int t) { + _function.attach(tptr, mptr); + setup(t); + } + + /* Function: detach + * Detach the function + */ + void detach(); + +#endif + +protected: + + virtual void handler(); + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/Timer.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/Timer.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,93 @@ +/* mbed Microcontroller Library - Timer + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_TIMER_H +#define MBED_TIMER_H + +#include "platform.h" +#include "PinNames.h" +#include "PeripheralNames.h" +#include "Base.h" + +namespace mbed { + +/* Class: Timer + * A general purpose timer + * + * Example: + * > // Count the time to toggle a LED + * > + * > #include "mbed.h" + * > + * > Timer timer; + * > DigitalOut led(LED1); + * > int begin, end; + * > + * > int main() { + * > timer.start(); + * > begin = timer.read_us(); + * > led = !led; + * > end = timer.read_us(); + * > printf("Toggle the led takes %d us", end - begin); + * > } + */ +class Timer : public Base { + +public: + + Timer(const char *name = NULL); + + /* Function: start + * Start the timer + */ + void start(); + + /* Function: stop + * Stop the timer + */ + void stop(); + + /* Function: reset + * Reset the timer to 0. + * + * If it was already counting, it will continue + */ + void reset(); + + /* Function: read + * Get the time passed in seconds + */ + float read(); + + /* Function: read_ms + * Get the time passed in mili-seconds + */ + int read_ms(); + + /* Function: read_us + * Get the time passed in micro-seconds + */ + int read_us(); + +#ifdef MBED_OPERATORS + operator float(); +#endif + +#ifdef MBED_RPC + virtual const struct rpc_method *get_rpc_methods(); + static struct rpc_class *get_rpc_class(); +#endif + +protected: + + int slicetime(); + int _running; // whether the timer is running + unsigned int _start; // the start time of the latest slice + int _time; // any accumulated time from previous slices + +}; + +} // namespace mbed + +#endif \ No newline at end of file
diff -r 000000000000 -r 80df663dd15e mbed/TimerEvent.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/TimerEvent.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,45 @@ +/* mbed Microcontroller Library - TimerEvent + * Copyright (c) 2007-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_TIMEREVENT_H +#define MBED_TIMEREVENT_H + +namespace mbed { + +// Base abstraction for timer interrupts +class TimerEvent { + +public: + + TimerEvent(); + + // The handler registered with the underlying timer interrupt + static void irq(); + + // Destruction removes it... + virtual ~TimerEvent(); + +protected: + + // The handler called to service the timer event of the derived class + virtual void handler() = 0; + + // insert in to linked list + void insert(unsigned int timestamp); + + // remove from linked list, if in it + void remove(); + + // Get the current usec timestamp + static unsigned int timestamp(); + + static TimerEvent *_head; // The head of the list of the events, NULL if none + TimerEvent *_next; // Pointer to the next in the list, NULL if last + unsigned int _timestamp; // The timestamp at which the even should be triggered + +}; + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/can_helper.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/can_helper.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,37 @@ +/* mbed Microcontroller Library - can_helper + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_CAN_HELPER_H +#define MBED_CAN_HELPER_H + +#ifdef __cplusplus +extern "C" { +#endif + +enum CANFormat { + CANStandard = 0, + CANExtended = 1 +}; +typedef enum CANFormat CANFormat; + +enum CANType { + CANData = 0, + CANRemote = 1 +}; +typedef enum CANType CANType; + +struct CAN_Message { + unsigned int id; // 29 bit identifier + unsigned char data[8]; // Data field + unsigned char len; // Length of data field in bytes + CANFormat format; // 0 - STANDARD, 1- EXTENDED IDENTIFIER + CANType type; // 0 - DATA FRAME, 1 - REMOTE FRAME +}; +typedef struct CAN_Message CAN_Message; + +#ifdef __cplusplus +}; +#endif + +#endif // MBED_CAN_HELPER_H
diff -r 000000000000 -r 80df663dd15e mbed/device.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/device.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,62 @@ + +#ifndef MBED_DEVICE_H +#define MBED_DEVICE_H + +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + +#define DEVICE_PORTIN 1 +#define DEVICE_PORTOUT 1 +#define DEVICE_PORTINOUT 1 + +#define DEVICE_INTERRUPTIN 1 + +#define DEVICE_ANALOGIN 1 +#define DEVICE_ANALOGOUT 1 + +#define DEVICE_SERIAL 1 + +#define DEVICE_I2C 1 +#define DEVICE_I2CSLAVE 1 + +#define DEVICE_SPI 1 +#define DEVICE_SPISLAVE 1 + +#define DEVICE_CAN 1 + +#define DEVICE_RTC 1 + +#define DEVICE_ETHERNET 1 + +#define DEVICE_PWMOUT 1 + +#elif defined(TARGET_LPC11U24) + +#define DEVICE_PORTIN 1 +#define DEVICE_PORTOUT 1 +#define DEVICE_PORTINOUT 1 + +#define DEVICE_INTERRUPTIN 1 + +#define DEVICE_ANALOGIN 1 +#define DEVICE_ANALOGOUT 0 + +#define DEVICE_SERIAL 1 + +#define DEVICE_I2C 1 +#define DEVICE_I2CSLAVE 1 + +#define DEVICE_SPI 1 +#define DEVICE_SPISLAVE 1 + +#define DEVICE_CAN 0 + +#define DEVICE_RTC 0 + +#define DEVICE_ETHERNET 0 + +#define DEVICE_PWMOUT 1 + +#endif + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/error.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/error.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,60 @@ +/* mbed Microcontroller Library - error + * Copyright (c) 2006-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_ERROR_H +#define MBED_ERROR_H + +/* Reporting Compile-Time Errors: + * To generate a fatal compile-time error, you can use the pre-processor #error directive. + * + * > #error "That shouldn't have happened!" + * + * If the compiler evaluates this line, it will report the error and stop the compile. + * + * For example, you could use this to check some user-defined compile-time variables: + * + * > #define NUM_PORTS 7 + * > #if (NUM_PORTS > 4) + * > #error "NUM_PORTS must be less than 4" + * > #endif + * + * Reporting Run-Time Errors: + * To generate a fatal run-time error, you can use the mbed error() function. + * + * > error("That shouldn't have happened!"); + * + * If the mbed running the program executes this function, it will print the + * message via the USB serial port, and then die with the blue lights of death! + * + * The message can use printf-style formatting, so you can report variables in the + * message too. For example, you could use this to check a run-time condition: + * + * > if(x >= 5) { + * > error("expected x to be less than 5, but got %d", x); + * > } + */ + +#if 0 // for documentation only +/* Function: error + * Report a fatal runtime error + * + * Outputs the specified error message to stderr so it will appear via the USB + * serial port, and then calls exit(1) to die with the blue lights of death. + * + * Variables: + * format - printf-style format string, followed by associated variables + */ +void error(const char* format, ...); +#endif + +#include <stdlib.h> + +#ifdef NDEBUG + #define error(...) (exit(1)) +#else + #include <stdio.h> + #define error(...) (fprintf(stderr, __VA_ARGS__), exit(1)) +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/mbed.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/mbed.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,59 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_H +#define MBED_H + +#define MBED_LIBRARY_VERSION 29 + +// Useful C libraries +#include <stdio.h> +#include <stdlib.h> +#include <string.h> +#include <math.h> +#include <time.h> + +// mbed Debug libraries + +#include "error.h" +#include "mbed_interface.h" + +// mbed Peripheral components + +#include "DigitalIn.h" +#include "DigitalOut.h" +#include "DigitalInOut.h" +#include "BusIn.h" +#include "BusOut.h" +#include "BusInOut.h" +#include "PortIn.h" +#include "PortInOut.h" +#include "PortOut.h" +#include "AnalogIn.h" +#include "AnalogOut.h" +#include "PwmOut.h" +#include "Serial.h" +#include "SerialHalfDuplex.h" +#include "SPI.h" +#include "SPISlave.h" +#include "SPIHalfDuplex.h" +#include "I2C.h" +#include "I2CSlave.h" +#include "Ethernet.h" +#include "CAN.h" + +// mbed Internal components +#include "Timer.h" +#include "Ticker.h" +#include "Timeout.h" +#include "LocalFileSystem.h" +#include "InterruptIn.h" +#include "wait_api.h" +#include "rtc_time.h" + +using namespace mbed; +using namespace std; + +#endif +
diff -r 000000000000 -r 80df663dd15e mbed/mbed_interface.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/mbed_interface.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,89 @@ +/* Title: mbed_interface + * Functions to control the mbed interface + * + * mbed Microcontrollers have a built-in interface to provide functionality such as + * drag-n-drop download, reset, serial-over-usb, and access to the mbed local file + * system. These functions provide means to control the interface suing semihost + * calls it supports. + */ + +/* mbed Microcontroller Library - mbed_interface + * Copyright (c) 2009-2011 ARM Limited. All rights reserved. + */ + +#ifndef MBED_INTERFACE_H +#define MBED_INTERFACE_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Function: mbed_interface_connected + * Determine whether the mbed interface is connected, based on whether debug is enabled + * + * Variables: + * returns - 1 if interface is connected, else 0 + */ +int mbed_interface_connected(void); + +/* Function: mbed_interface_reset + * Instruct the mbed interface to reset, as if the reset button had been pressed + * + * Variables: + * returns - 1 if successful, else 0 (e.g. interface not present) + */ +int mbed_interface_reset(void); + +/* Function: mbed_interface_disconnect + * This will disconnect the debug aspect of the interface, so semihosting will be disabled. + * The interface will still support the USB serial aspect + * + * Variables: + * returns - 0 if successful, else -1 (e.g. interface not present) + */ +int mbed_interface_disconnect(void); + +/* Function: mbed_interface_powerdown + * This will disconnect the debug aspect of the interface, and if the USB cable is not + * connected, also power down the interface. If the USB cable is connected, the interface + * will remain powered up and visible to the host + * + * Variables: + * returns - 0 if successful, else -1 (e.g. interface not present) + */ +int mbed_interface_powerdown(void); + +/* Function: mbed_interface_uid + * This returns a string containing the 32-character UID of the mbed interface + * + * This is a weak function that can be overwritten if required + * + * Variables: + * uid - A 33-byte array to write the null terminated 32-byte string + * returns - 0 if successful, else -1 (e.g. interface not present) + */ +int mbed_interface_uid(char *uid); + +/* Function: mbed_mac_address + * This returns a unique 6-byte MAC address, based on the interface UID + * + * If the interface is not present, it returns a default fixed MAC address (00:02:F7:F0:00:00) + * + * This is a weak function that can be overwritten if you want to provide your own mechanism to + * provide a MAC address. + + * Variables: + * mac - A 6-byte array to write the MAC address + */ +void mbed_mac_address(char *mac); + +/* Function: mbed_die + * Cause the mbed to flash the BLOD LED sequence + */ +void mbed_die(void); + +#ifdef __cplusplus +} +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/platform.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/platform.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,12 @@ +/* mbed Microcontroller Library - platform + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_PLATFORM_H +#define MBED_PLATFORM_H + +#define MBED_RPC + +#define MBED_OPERATORS + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/rpc.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/rpc.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,592 @@ +/* mbed Microcontroller Library - RPC + * Copyright (c) 2008-2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_RPC_H +#define MBED_RPC_H + +/* Section rpc + * Helpers for rpc handling. + */ + +#include <stdlib.h> +#include <stdio.h> +#include <string.h> +#include <ctype.h> +#include "Base.h" + +#include "PinNames.h" +#include <stdint.h> + +namespace mbed { + +/* Function parse_arg + * Parses and returns a value from a string. + * + * Variable + * arg - The string to pase + * next - If not NULL a pointer to after the last + * character parsed is written here + */ +template<typename T> T parse_arg(const char *arg, const char **next); + +inline char parse_char(const char *arg, const char **next) { + char c = *arg++; + if(c == '\\') { + c = *arg++; + switch(c) { + case 'a': c = '\a'; break; + case 'b': c = '\b'; break; + case 't': c = '\t'; break; + case 'n': c = '\n'; break; + case 'v': c = '\v'; break; + case 'f': c = '\f'; break; + case 'r': c = '\r'; break; + case 'x': + { + /* two-character hexadecimal */ + char buf[3]; + buf[0] = *arg++; + buf[1] = *arg++; + buf[2] = 0; + c = strtol(buf, NULL, 16); + } + break; + default: + if(isdigit(c)) { + /* three-character octal */ + char buf[4]; + buf[0] = c; + buf[1] = *arg++; + buf[2] = *arg++; + buf[3] = 0; + c = strtol(buf, NULL, 8); + } + break; + } + } + *next = arg; + return c; +} + +/* signed integer types */ + +template<> inline int parse_arg<int>(const char *arg, const char **next) { + if(arg[0] == '\'') { + char c = parse_char(arg+1, &arg); + if(next != NULL) *next = arg+1; + return c; + } else { + return strtol(arg, const_cast<char**>(next), 0); + } +} + +template<> inline char parse_arg<char>(const char *arg, const char **next) { + return parse_arg<int>(arg,next); +} + +template<> inline short int parse_arg<short int>(const char *arg, const char **next) { + return parse_arg<int>(arg,next); +} + +template<> inline long int parse_arg<long int>(const char *arg, const char **next) { + return parse_arg<int>(arg,next); +} + +template<> inline long long parse_arg<long long>(const char *arg, const char **next) { + return strtoll(arg, const_cast<char**>(next), 0); +} + +/* unsigned integer types */ + +template<> inline unsigned int parse_arg<unsigned int>(const char *arg, const char **next) { + if(arg[0] == '\'') { + char c = parse_char(arg+1, &arg); + if(next != NULL) *next = arg+1; + return c; + } else { + return strtoul(arg, const_cast<char**>(next), 0); + } +} + +template<> inline unsigned char parse_arg<unsigned char>(const char *arg, const char **next) { + return parse_arg<unsigned int>(arg,next); +} + +template<> inline unsigned short int parse_arg<unsigned short int>(const char *arg, const char **next) { + return parse_arg<unsigned int>(arg,next); +} + +template<> inline unsigned long int parse_arg<unsigned long int>(const char *arg, const char **next) { + return parse_arg<unsigned int>(arg,next); +} + +template<> inline unsigned long long parse_arg<unsigned long long>(const char *arg, const char **next) { + return strtoull(arg, const_cast<char**>(next), 0); +} + +/* floating types */ + +template<> inline float parse_arg<float>(const char *arg, const char **next) { +#if !defined(__ARMCC_VERSION) || __ARMCC_VERSION >= 410000 + return strtof(arg,const_cast<char**>(next)); +#elif __ARMCC_VERSION >= 310000 + /* bug in header means no using declaration for strtof */ + return std::strtof(arg,const_cast<char**>(next)); +#else + /* strtof not supported */ + return strtod(arg,const_cast<char**>(next)); +#endif +} + +template<> inline double parse_arg<double>(const char *arg, const char **next) { + return strtod(arg,const_cast<char**>(next)); +} + +template<> inline long double parse_arg<long double>(const char *arg, const char **next) { + return strtod(arg,const_cast<char**>(next)); +} + +/* string */ + +template<> inline char *parse_arg<char*>(const char *arg, const char **next) { + const char *ptr = arg; + char *res = NULL; + if(*arg == '"') { + /* quoted string */ + ptr = ++arg; + int len = 0; + /* find the end (and length) of the quoted string */ + for(char c = *ptr; c != 0 && c != '"'; c = *++ptr) { + len++; + if(c == '\\') { + ptr++; + } + } + /* copy the quoted string, and unescape characters */ + if(len != 0) { + res = new char[len+1]; + char *resptr = res; + while(arg != ptr) { + *resptr++ = parse_char(arg, &arg); + } + *resptr = 0; + } + } else { + /* unquoted string */ + while(isalnum(*ptr) || *ptr=='_') { + ptr++; + } + int len = ptr-arg; + if(len!=0) { + res = new char[len+1]; + memcpy(res, arg, len); + res[len] = 0; + } + } + + if(next != NULL) { + *next = ptr; + } + return res; +} + +template<> inline const char *parse_arg<const char*>(const char *arg, const char **next) { + return parse_arg<char*>(arg,next); +} + +/* Pins */ + + +inline PinName parse_pins(const char *str) { + const PinName pin_names[] = {p5, p6, p7, p8, p9, p10, p11, p12, p13, p14 + , p15, p16, p17, p18, p19, p20, p21, p22, p23 + , p24, p25, p26, p27, p28, p29, p30}; + + if(str[0] == 'P') { // Pn_n + uint32_t port = str[1] - '0'; + uint32_t pin = str[3] - '0'; // Pn_n + uint32_t pin2 = str[4] - '0'; // Pn_nn + if(pin2 <= 9) { + pin = pin * 10 + pin2; + } +#if defined(TARGET_LPC1768) || defined(TARGET_LPC2368) + return (PinName)(LPC_GPIO0_BASE + port * 32 + pin); +#elif defined(TARGET_LPC11U24) + return (PinName)(port * 32 + pin); +#endif + } else if(str[0] == 'p') { // pn + uint32_t pin = str[1] - '0'; // pn + uint32_t pin2 = str[2] - '0'; // pnn + if(pin2 <= 9) { + pin = pin * 10 + pin2; + } + if(pin < 5 || pin > 30) { + return NC; + } + return pin_names[pin - 5]; + } else if(str[0] == 'L') { // LEDn + switch(str[3]) { + case '1' : return LED1; + case '2' : return LED2; + case '3' : return LED3; + case '4' : return LED4; + } + } else if(str[0] == 'U') { // USB?X + switch(str[3]) { + case 'T' : return USBTX; + case 'R' : return USBRX; + } + } + return NC; +} + +template<> inline PinName parse_arg<PinName>(const char *arg, const char **next) { + const char *ptr = arg; + PinName pinname = NC; + while(isalnum(*ptr) || *ptr=='_') { + ptr++; + } + int len = ptr-arg; + if(len!=0) { + pinname = parse_pins(arg); + + } + if(next != NULL) { + *next = ptr; + } + return pinname; +} + + +/* Function write_result + * Writes a value in to a result string in an appropriate manner + * + * Variable + * val - The value to write + * result - A pointer to the array to write the value into + */ +template<typename T> void write_result(T val, char *result); + +/* signed integer types */ + +template<> inline void write_result<char>(char val, char *result) { + result[0] = val; + result[1] = '\0'; +} + +template<> inline void write_result<short int>(short int val, char *result) { + sprintf(result, "%hi", val); +} + +template<> inline void write_result<int>(int val, char *result) { + sprintf(result, "%i", val); +} + +template<> inline void write_result<long int>(long int val, char *result) { + sprintf(result, "%li", val); +} + +template<> inline void write_result<long long int>(long long int val, char *result) { + sprintf(result, "%lli", val); +} + +/* unsigned integer types */ + +template<> inline void write_result<unsigned char>(unsigned char val, char *result) { + result[0] = val; + result[1] = '\0'; +} + +template<> inline void write_result<unsigned short int>(unsigned short int val, char *result) { + sprintf(result, "%hu", val); +} + +template<> inline void write_result<unsigned int>(unsigned int val, char *result) { + sprintf(result, "%u", val); +} + +template<> inline void write_result<unsigned long int>(unsigned long int val, char *result) { + sprintf(result, "%lu", val); +} + +template<> inline void write_result<unsigned long long int>(unsigned long long int val, char *result) { + sprintf(result, "%llu", val); +} + +/* floating types */ + +template<> inline void write_result<float>(float val, char *result) { + sprintf(result, "%.17g", val); +} + +template<> inline void write_result<double>(double val, char *result) { + sprintf(result, "%.17g", val); +} + +template<> inline void write_result<long double>(long double val, char *result) { + sprintf(result, "%.17Lg", val); +} + + +/* string */ + +template<> inline void write_result<char*>(char *val, char *result) { + if(val==NULL) { + result[0] = 0; + } else { + strcpy(result, val); + } +} + +template<> inline void write_result<const char*>(const char *val, char *result) { + if(val==NULL) { + result[0] = 0; + } else { + strcpy(result, val); + } +} + + +inline const char *next_arg(const char* next) { + while(*next == ' ') next++; + if(*next == ',' || *next == '?') next++; + while(*next == ' ') next++; + return next; +} + + +/* Function rpc_method_caller + */ +template<class T, void (T::*member)(const char *,char *)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + (static_cast<T*>(this_ptr)->*member)(arguments,result); +} + + +/* Function rpc_method_caller + */ +template<class T, void (T::*member)()> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + (static_cast<T*>(this_ptr)->*member)(); + if(result != NULL) { + result[0] = '\0'; + } +} + + +/* Function rpc_method_caller + */ +template<class T, typename A1, void (T::*member)(A1)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),NULL); + + (static_cast<T*>(this_ptr)->*member)(arg1); + if(result != NULL) { + result[0] = '\0'; + } +} + + +/* Function rpc_method_caller + */ +template<class T, typename A1, typename A2, void (T::*member)(A1,A2)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),NULL); + + (static_cast<T*>(this_ptr)->*member)(arg1,arg2); + if(result != NULL) { + result[0] = '\0'; + } +} + + +/* Function rpc_method_caller + */ +template<class T, typename A1, typename A2, typename A3, void (T::*member)(A1,A2,A3)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),&next); + A3 arg3 = parse_arg<A3>(next_arg(next),NULL); + + (static_cast<T*>(this_ptr)->*member)(arg1,arg2,arg3); + if(result != NULL) { + result[0] = '\0'; + } +} + + +/* Function rpc_method_caller + */ +template<typename R, class T, R (T::*member)()> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + R res = (static_cast<T*>(this_ptr)->*member)(); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_method_caller + */ +template<typename R, class T, typename A1, R (T::*member)(A1)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),NULL); + + R res = (static_cast<T*>(this_ptr)->*member)(arg1); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_method_caller + */ +template<typename R, class T, typename A1, typename A2, R (T::*member)(A1,A2)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),NULL); + + R res = (static_cast<T*>(this_ptr)->*member)(arg1,arg2); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_method_caller + */ +template<typename R, class T, typename A1, typename A2, typename A3, R (T::*member)(A1,A2,A3)> +void rpc_method_caller(Base *this_ptr, const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),&next); + A3 arg3 = parse_arg<A3>(next_arg(next),NULL); + + R res = (static_cast<T*>(this_ptr)->*member)(arg1,arg2,arg3); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_function caller + */ +template<typename R, R (*func)()> +void rpc_function_caller(const char *arguments, char *result) { + R res = (*func)(); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_function caller + */ +template<typename R, typename A1, R (*func)(A1)> +void rpc_function_caller(const char *arguments, char *result) { + A1 arg1 = parse_arg<A1>(next_arg(arguments),NULL); + R res = (*func)(arg1); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_function caller + */ +template<typename R, typename A1, typename A2, R (*func)(A1,A2)> +void rpc_function_caller(const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),NULL); + + R res = (*func)(arg1,arg2); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_function caller + */ +template<typename R, typename A1, typename A2, typename A3, R (*func)(A1,A2,A3)> +void rpc_function_caller(const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),&next); + A3 arg3 = parse_arg<A3>(next_arg(next),NULL); + + R res = (*func)(arg1,arg2,arg3); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +/* Function rpc_function caller + */ +template<typename R, typename A1, typename A2, typename A3, typename A4, R (*func)(A1,A2,A3,A4)> +void rpc_function_caller(const char *arguments, char *result) { + + const char *next = arguments; + A1 arg1 = parse_arg<A1>(next_arg(next),&next); + A2 arg2 = parse_arg<A2>(next_arg(next),&next); + A3 arg3 = parse_arg<A3>(next_arg(next),&next); + A4 arg4 = parse_arg<A4>(next_arg(next),NULL); + + R res = (*func)(arg1,arg2,arg3,arg4); + if(result != NULL) { + write_result<R>(res, result); + } +} + + +struct rpc_method { + const char *name; + typedef void (*caller_t)(Base*, const char*, char*); + typedef const struct rpc_method *(*super_t)(Base*); + union { + caller_t caller; + super_t super; + }; +}; + +template<class C> +const struct rpc_method *rpc_super(Base *this_ptr) { + return static_cast<C*>(this_ptr)->C::get_rpc_methods(); +} + +#define RPC_METHOD_END { NULL, NULL } +#define RPC_METHOD_SUPER(C) { NULL, (rpc_method::caller_t)(rpc_method::super_t)rpc_super<C> } + +/* Function rpc + * Parse a string describing a call and then do it + * + * Variables + * call - A pointer to a string describing the call, which has + * the form /object/method arg ... argn. Arguments are + * delimited by space characters, and the string is terminated + * by a null character. + * result - A pointer to an array to write the result into. + */ +bool rpc(const char *buf, char *result = 0); + + +} // namespace mbed + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/rtc_time.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/rtc_time.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,206 @@ +/* Title: time + * Implementation of the C time.h functions + * + * Provides mechanisms to set and read the current time, based + * on the microcontroller Real-Time Clock (RTC), plus some + * standard C manipulation and formating functions. + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > set_time(1256729737); // Set RTC time to Wed, 28 Oct 2009 11:35:37 + * > + * > while(1) { + * > time_t seconds = time(NULL); + * > + * > printf("Time as seconds since January 1, 1970 = %d\n", seconds); + * > + * > printf("Time as a basic string = %s", ctime(&seconds)); + * > + * > char buffer[32]; + * > strftime(buffer, 32, "%I:%M %p\n", localtime(&seconds)); + * > printf("Time as a custom formatted string = %s", buffer); + * > + * > wait(1); + * > } + * > } + */ + +/* mbed Microcontroller Library - rtc_time + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#include <time.h> + +#ifdef __cplusplus +extern "C" { +#endif + +#if 0 // for documentation only +/* Function: time + * Get the current time + * + * Returns the current timestamp as the number of seconds since January 1, 1970 + * (the UNIX timestamp). The value is based on the current value of the + * microcontroller Real-Time Clock (RTC), which can be set using <set_time>. + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > time_t seconds = time(NULL); + * > printf("It is %d seconds since January 1, 1970\n", seconds); + * > } + * + * Variables: + * t - Pointer to a time_t to be set, or NULL if not used + * returns - Number of seconds since January 1, 1970 (the UNIX timestamp) + */ +time_t time(time_t *t); +#endif + +/* Function: set_time + * Set the current time + * + * Initialises and sets the time of the microcontroller Real-Time Clock (RTC) + * to the time represented by the number of seconds since January 1, 1970 + * (the UNIX timestamp). + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > set_time(1256729737); // Set time to Wed, 28 Oct 2009 11:35:37 + * > } + * + * Variables: + * t - Number of seconds since January 1, 1970 (the UNIX timestamp) + */ +void set_time(time_t t); + +#if 0 // for documentation only +/* Function: mktime + * Converts a tm structure in to a timestamp + * + * Converts the tm structure in to a timestamp in seconds since January 1, 1970 + * (the UNIX timestamp). The values of tm_wday and tm_yday of the tm structure + * are also updated to their appropriate values. + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > // setup time structure for Wed, 28 Oct 2009 11:35:37 + * > struct tm t; + * > t.tm_sec = 37; // 0-59 + * > t.tm_min = 35; // 0-59 + * > t.tm_hour = 11; // 0-23 + * > t.tm_mday = 28; // 1-31 + * > t.tm_mon = 9; // 0-11 + * > t.tm_year = 109; // year since 1900 + * > + * > // convert to timestamp and display (1256729737) + * > time_t seconds = mktime(&t); + * > printf("Time as seconds since January 1, 1970 = %d\n", seconds); + * > } + * + * Variables: + * t - The tm structure to convert + * returns - The converted timestamp + */ +time_t mktime(struct tm *t); +#endif + +#if 0 // for documentation only +/* Function: localtime + * Converts a timestamp in to a tm structure + * + * Converts the timestamp pointed to by t to a (statically allocated) + * tm structure. + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > time_t seconds = 1256729737; + * > struct tm *t = localtime(&seconds); + * > } + * + * Variables: + * t - Pointer to the timestamp + * returns - Pointer to the (statically allocated) tm structure + */ +struct tm *localtime(const time_t *t); +#endif + +#if 0 // for documentation only +/* Function: ctime + * Converts a timestamp to a human-readable string + * + * Converts a time_t timestamp in seconds since January 1, 1970 (the UNIX + * timestamp) to a human readable string format. The result is of the + * format: "Wed Oct 28 11:35:37 2009\n" + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > time_t seconds = time(NULL); + * > printf("Time as a string = %s", ctime(&seconds)); + * > } + * + * Variables: + * t - The timestamp to convert + * returns - Pointer to a (statically allocated) string containing the + * human readable representation, including a '\n' character + */ +char *ctime(const time_t *t); +#endif + +#if 0 // for documentation only +/* Function: strftime + * Converts a tm structure to a custom format human-readable string + * + * Creates a formated string from a tm structure, based on a string format + * specifier provided. + * + * Format Specifiers: + * %S - Second (00-59) + * %M - Minute (00-59) + * %H - Hour (00-23) + * %d - Day (01-31) + * %m - Month (01-12) + * %Y/%y - Year (2009/09) + * + * %A/%a - Weekday Name (Monday/Mon) + * %B/%b - Month Name (January/Jan) + * %I - 12 Hour Format (01-12) + * %p - "AM" or "PM" + * %X - Time (14:55:02) + * %x - Date (08/23/01) + * + * Example: + * > #include "mbed.h" + * > + * > int main() { + * > time_t seconds = time(NULL); + * > + * > char buffer[32]; + * > strftime(buffer, 32, "%I:%M %p\n", localtime(&seconds)); + * > printf("Time as a formatted string = %s", buffer); + * > } + * + * Variables: + * buffer - String buffer to store the result + * max - Maximum number of characters to store in the buffer + * format - Format specifier string + * t - Pointer to the tm structure to convert + * returns - Number of characters copied + */ +size_t strftime(char *buffer, size_t max, const char *format, const struct tm *t); +#endif + +#ifdef __cplusplus +} +#endif
diff -r 000000000000 -r 80df663dd15e mbed/us_ticker_api.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/us_ticker_api.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,20 @@ +/* mbed Microcontroller Library - us_ticker_api + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_US_TICKER_API_H +#define MBED_US_TICKER_API_H + +#include <stdint.h> + +#ifdef __cplusplus +extern "C" { +#endif + +uint32_t us_ticker_read(void); + +#ifdef __cplusplus +} +#endif + +#endif
diff -r 000000000000 -r 80df663dd15e mbed/wait_api.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed/wait_api.h Fri May 19 14:32:14 2017 +0000 @@ -0,0 +1,94 @@ +/* Title: wait + * Generic wait functions. + * + * These provide simple NOP type wait capabilities. + * + * Example: + * > #include "mbed.h" + * > + * > DigitalOut heartbeat(LED1); + * > + * > int main() { + * > while (1) { + * > heartbeat = 1; + * > wait(0.5); + * > heartbeat = 0; + * > wait(0.5); + * > } + * > } + */ + +/* mbed Microcontroller Library - wait_api + * Copyright (c) 2009 ARM Limited. All rights reserved. + */ + +#ifndef MBED_WAIT_API_H +#define MBED_WAIT_API_H + +#ifdef __cplusplus +extern "C" { +#endif + +/* Function: wait + * Waits for a number of seconds, with microsecond resolution (within + * the accuracy of single precision floating point). + * + * Variables: + * s - number of seconds to wait + */ +void wait(float s); + +/* Function: wait_ms + * Waits a number of milliseconds. + * + * Variables: + * ms - the whole number of milliseconds to wait + */ +void wait_ms(int ms); + +/* Function: wait_us + * Waits a number of microseconds. + * + * Variables: + * us - the whole number of microseconds to wait + */ +void wait_us(int us); + +#ifdef TARGET_LPC11U24 +/* Function: sleep + * Send the microcontroller to sleep + * + * The processor is setup ready for sleep, and sent to sleep using __WFI(). In this mode, the + * system clock to the core is stopped until a reset or an interrupt occurs. This eliminates + * dynamic power used by the processor, memory systems and buses. The processor, peripheral and + * memory state are maintained, and the peripherals continue to work and can generate interrupts. + * + * The processor can be woken up by any internal peripheral interrupt or external pin interrupt. + * + * Note: The mbed interface semihosting is disconnected as part of going to sleep, and can not be restored. + * Flash re-programming and the USB serial port will remain active, but the mbed program will no longer be + * able to access the LocalFileSystem + */ +void sleep(void); + +/* Function: deepsleep + * Send the microcontroller to deep sleep + * + * This processor is setup ready for deep sleep, and sent to sleep using __WFI(). This mode + * has the same sleep features as sleep plus it powers down peripherals and clocks. All state + * is still maintained. + * + * The processor can only be woken up by an external interrupt on a pin or a watchdog timer. + * + * Note: The mbed interface semihosting is disconnected as part of going to sleep, and can not be restored. + * Flash re-programming and the USB serial port will remain active, but the mbed program will no longer be + * able to access the LocalFileSystem + */ +void deepsleep(void); +#endif + +#ifdef __cplusplus +} +#endif + +#endif