For Wire Hand
Dependencies: mbed mbed-rtos EthernetInterface
Revision 0:88bfb16a6ad5, committed 2020-04-24
- Comitter:
- Masayoshi
- Date:
- Fri Apr 24 03:11:11 2020 +0000
- Commit message:
- KYOSO edition
Changed in this revision
diff -r 000000000000 -r 88bfb16a6ad5 .mbed --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/.mbed Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,1 @@ +ROOT=.
diff -r 000000000000 -r 88bfb16a6ad5 EthernetInterface.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/EthernetInterface.lib Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/teams/SiSK/code/EthernetInterface/#d7bd7384a37c
diff -r 000000000000 -r 88bfb16a6ad5 fdc.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/fdc.h Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,185 @@ +/*----------------------------------------------------------------- + * fdc.h + */ +// debug port +DigitalOut d19(p19); +DigitalOut d20(p20); +DigitalOut d21(p21); +DigitalOut d22(p22); +DigitalOut d23(p23); +DigitalOut d24(p24); +DigitalOut d25(p25); +DigitalOut d26(p26); + +//static const char * DST_ADDRESS = "192.168.140.2"; +//static const char * MY_ADDRESS = "192.168.140.8"; +//static const int DST_PORT = 6008; +//static const int MY_PORT = 6008; +//static const char * NETMASK = "255.255.0.0"; +//static const char * GATEWAY = "0.0.0.0"; + +//static const int USB_BAUDRATE = 9600; + +static const uint8_t ADDR_I2C = 0xFF; //Address on FDC1004 for measurement register +static const uint8_t REG_FDC = 0xA0; //int REG_FDC = 80; //Address on FDC1004 for measurement register b1010000 +static const uint8_t REG_MUX = 0xE0; //int REG_MEX =112; //Address on PCA9548 for measurement register b1110000 +static char FDC_CONFIG[] = {0x08, 0x09, 0x0A, 0x0B}; +static char FDC_MSB[] = {0x00, 0x02, 0x04, 0x06}; +static char FDC_LSB[] = {0x01, 0x03, 0x05, 0x07}; + +static const int FDC_NUM1 = 2; +static const int FDC_NUM2 = 1; +static const int FDC_NUM = FDC_NUM1 + FDC_NUM2; //MUXに接続しているFDC1004の数、ch0から順に接続 +//static const int NUM_AXES = 4; +static const int NUM_DEN = 4; // DENKYOKU +//static const int UDP_TX_SIZE = sizeof(float) * FDC_NUM * NUM_AXES; + +//union UdpTx { +// float data[FDC_NUM][NUM_AXES]; +// char bytes[4*FDC_NUM*NUM_AXES]; +//}; + +//RawSerial pc(USBTX, USBRX); +//I2C i2c(p9, p10); +//DigitalOut led1(LED1); + +/*static void setupUdp(UDPSocket& sock) { + EthernetInterface eth; + + pc.printf("Setup UDP\r\n"); + + eth.init(MY_ADDRESS, NETMASK, GATEWAY); + pc.printf("eth.init()\r\n"); + eth.connect(15000); + pc.printf("eth.connect()\r\n"); + + const char *ip = eth.getIPAddress(); + pc.printf("IP: %s\r\n", ip ? ip : "No IP"); + + sock.bind(MY_PORT); + pc.printf("Port: %d\r\n", MY_PORT); +}*/ + +/* PCA9548を使ったch切替 */ +static inline bool switchI2c(I2C *i2c, uint8_t ch) { + bool ret = true; + char cmd[1] = {1 << ch}; + int result = i2c->write(REG_MUX, cmd, 1, false); + if (result != 0) { // Error + //pc.printf("switchI2c error \r\n"); +//ERROR +d22 = !d22; +//wait(0.2); +d22 = !d22; + ret = false; + } + return ret; +} + +/* FDC1004の設定をする関数 */ +static inline bool initFdc(I2C *i2c){ + char cmd1[3] = {0x0C, 0x80, 0x00}; + char cmd2[1] = {ADDR_I2C}; + i2c->write(REG_FDC, cmd1, 3, false); + i2c->write(REG_FDC, cmd2, 1, false); // DeviceIDの確認 + + //idチェック 16,4 と出たらOK。 + char res[2]; + i2c->read(REG_FDC, res, 2); + + return res[0] == 16 && res[1] == 4; +} + +static inline uint8_t highByte(uint16_t x) { + return (x >> 8) & 0xFF; +} + +static inline uint8_t lowByte(uint16_t x) { + return (x >> 0) & 0xFF; +} + +static inline void config(I2C *i2c, int rate, int (&capdac)[NUM_DEN]){ + // rate設定 1:100S/s, 2:200S/s, 3:400S/s + + uint16_t conf_fdc, conf_meas; + + // conf_fdc 測定頻度と使うチャンネルを設定 + conf_fdc = (rate << 10) + (1 << 8) + (0b1111 << 4); + char cmd[3] = {0x0C, highByte(conf_fdc), lowByte(conf_fdc)}; + i2c->write(REG_FDC, cmd, 3, false); + + // conf_meas CAPDACの設定 + for(int i=0; i<4;i++){ + if(capdac[i] >= 0){ + conf_meas = (i << 13) + (0b100 << 10) + (capdac[i] << 5); + } else if (capdac[i] == -1){ + conf_meas = (i << 13) + (0b111 << 10); + } + cmd[0] = FDC_CONFIG[i]; + cmd[1] = highByte(conf_meas); + cmd[2] = lowByte(conf_meas); + int result = i2c->write(REG_FDC, cmd, 3, false); + } +} + +static inline int readRegister(I2C *i2c, char address) { + char cmd[1] = {address}; + char res[2]; + + i2c->write(REG_FDC, cmd, 1, true); // no stop + i2c->read (REG_FDC, res, 2); + return (int)((int)res[0] << 8) | res[1]; +} + +static inline int readMeas(I2C *i2c, int i) { + int msb = readRegister(i2c, FDC_MSB[i]); + return (msb << 8); +} + +static inline void senseCapacitance(I2C *i2c, float (&c)[NUM_DEN], int (&capdac)[NUM_DEN]){ + for (int i=0; i<NUM_DEN; i++) { + c[i] = ((float)readMeas(i2c, i)/0x80000); + if (c[i] >= 16) { + c[i] -= 32; + } + if (capdac[i] > 0) { + c[i] += float(capdac[i]) * 3.125f / 0x80000; + } + } +} + +// TODO リファクタリング後の関数(senseCapacitance)が、元の関数と同じ値になるか要検証 +/*static void senseCapacitance_orig(float (&c)[NUM_AXES], int (&capdac)[NUM_AXES]){ + unsigned int mbb1, mbb2, mbb3; // variables to store 16-bit unsigned integers + char res1[2]; + char res2[1]; + + for(int i=0; i<NUM_AXES; i++){ + i2c.write(REG_FDC, FDC_MSB + i, 1, true); + i2c.read(REG_FDC, res1, 2); + + i2c.write(REG_FDC, FDC_LSB + i, 1, true); + i2c.read(REG_FDC, res2, 1); + + // Below are the calculations to take the 24-bit measurement and convert into capacitance for MEAS1 + // * From datasheet: p.16 Section 8.6.1.1 shows the formula (all we need to do is shift the 24-bit value right by 19) + // ** Shifting by 19 takes a 24 bit number and makes it a 5 bit number with 19 bits after the decimal point + mbb1 = res1[0] * 256 + res1[1]; // Puts 16 most significant bits into one integer for left sensor measurement + mbb2 = mbb1 >> 11; // Sets mbb2 to the 5 bits that exist before the decimal point pFの整数部分5bit + mbb3 = 0b0000011111111111 & mbb1; // Sets mbb3 to the 11 bits that exist after the decimal point pFの小数点以下の11bit + + c[i] = (float)mbb2 + (float)mbb3 / 2048 + (float)res2[0] / 524288; // 単位pF + if (capdac[i] > 0) { + c[i] += float(capdac[i]) * float(3.125); //CAPDACによるoffset追加 + } + } +}*/ + +/*static void displayValues(float (&values)[FDC_NUM][NUM_AXES]) { + for (int j=0; j<FDC_NUM; j++) { + for(int i=0; i<NUM_AXES; i++) { + pc.printf("|%5.2f|", values[j][i]); + } + } + pc.printf("\r\n"); +}*/ \ No newline at end of file
diff -r 000000000000 -r 88bfb16a6ad5 main.cpp --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,401 @@ +/*------------------------------------------------------------------------------ + * LPC1768_OC_MULTIMODAL + * + * <DEBUG PORT> + * d19 MAIL-LOOP TOGGLE + * d20 UART1 + * d21 UART3 + * d22 ERROR mutil-plexer etc. + * d23 + * d24 UDP RECEIVE + * d25 UDP SEND + * d26 I2C + */ +#include "mbed.h" +#include "UDPSocket.h" +#include "fdc.h" +#include "EthernetInterface.h" + +#define SERIAL_CH 2 +#define I2C_CH 2 + +// Constants +static const int NUM_AXES1 = 5; +static const int NUM_AXES2 = 4; + +//static const int TX_BYTE_SIZE = 3; +//static const int RX_BYTE_SIZE = 3; +//static const int RX_RETRY_MAX = 200; +static const int NUM_AXES = NUM_AXES1 + NUM_AXES2; +//static const int UDP_TX_SIZE = sizeof(float) * NUM_AXES; // send to pc +//static const int UDP_RX_SIZE = sizeof(float) * NUM_AXES; // recv from pc +//static const int USB_BAUDRATE = 9600; +static const int ICS_BAUDRATE = 1250000; +static const int POS_MID = 7500; +static const int POS_FREE = 255; +static const uint8_t POS_COMMAND = 0x80; +static const char * NETMASK = "255.255.0.0"; +static const char * GATEWAY = "0.0.0.0"; +static const char * PC_ADDRESS = "192.168.1.2"; +static const char * MY_ADDRESS = "192.168.1.3"; +static const int PC_RX_PORT = 5000; // from pc +static const int PC_TX_PORT = 5001; // to pc +//static const int MY_PORT = 6007; +static const float MAX_DIFF_DEG = 10; + +RawSerial *p_serial1, *p_serial2;; +I2C *p_i2c1, *p_i2c2; +UDPSocket s_sock; +UDPSocket r_sock; + +DigitalOut led1(LED1); +DigitalOut led2(LED2); +DigitalOut led3(LED3); +DigitalOut led4(LED4); + +// finish +uint8_t g_finish = 0; // b0:uart1 b1:uart2 b2:i2c1 b3:i2c2 +uint8_t g_next = 0; + +// finish bit +#define BIT_SERIAL1 0x01 +#define BIT_SERIAL2 0x02 +#define BIT_I2C1 0x04 +#define BIT_I2C2 0x08 + + +// udp data +typedef struct { + uint16_t seq; + uint16_t dmy; + float motorData[NUM_AXES]; // 9*4=36byte +} data_t; +union RxUnion { + data_t d; + char buf[sizeof(data_t)]; +}; +typedef struct { + uint16_t seq; + uint16_t dmy; + float motorData[NUM_AXES]; // 9*4=36byte + float sensorData[FDC_NUM][NUM_DEN]; // 3*4*4=48byte +} data2_t; +union TxUnion { + data2_t d; + char buf[sizeof(data2_t)]; +}; +RxUnion g_rx = {0}; +TxUnion g_tx = {0}; + +Endpoint ep_pc_tx, ep_pc_rx; + +// for motor value +uint8_t g_res1[3], g_res2[3]; // motor response +uint8_t g_n1, g_n2; // motor response index +int g_echoCount1, g_echoCount2; // motor command echo counter +uint8_t g_id1, g_id2; // motor id +char g_cmd1[4], g_cmd2[4]; // motor command + +static inline void GenCommand(uint8_t id/*1,2,...*/, float cmd_deg, char *cmd/*OUT*/){ + int32_t cmd_fit = POS_MID - int(cmd_deg * 1000 / 34.0); + cmd[0] = uint8_t(POS_COMMAND | id); + cmd[1] = uint8_t(cmd_fit >> 7); + cmd[2] = uint8_t(cmd_fit & 0x7F); + cmd[3] = 0; // null +} +static inline float ParseResponse(uint8_t id/*1,2,...*/, uint8_t *p, float pre_deg){ + int act_fit = ((*(p+1) & 0x7F) << 7) + (*(p+2) & 0x7F); + float act_deg = 34 * (POS_MID - act_fit) / 1000.0; + act_deg = fabs(act_deg - pre_deg) > MAX_DIFF_DEG ? pre_deg : act_deg; + return act_deg; +} + +/*Ticker ticker; +int g_tmCnt = 0; +uint8_t g_tmReq = 0; +static void tick_handler(){ + if(--g_tmCnt <= 0){ + if(g_tmReq == 1){ + g_tmReq = 0; + led4 = 1; + } + } +}*/ + +static inline void wait_us(uint32_t microsec){ + wait(microsec * 1e-6); +} +static inline void Serial1_puts(float val){ + GenCommand(g_id1+1, val, g_cmd1); // cmd is 3byte + NULL + g_echoCount1 = 0; + g_n1 = 0; + p_serial1->putc(g_cmd1[0]); // async + //p_serial1->putc(g_cmd1[1]); // async + //p_serial1->putc(g_cmd1[2]); // async +} +static inline void Serial2_puts(float val){ + GenCommand(g_id2+1, val, g_cmd2); // cmd is 3byte + NULL + g_echoCount2 = 0; + g_n2 = 0; + p_serial2->putc(g_cmd2[0]); // async + //p_serial2->putc(g_cmd2[1]); // async + //p_serial2->putc(g_cmd2[2]); // async +} + +static inline void Serial1_Rx(){ + g_next++; + // first is echoback. second is motor response. + uint8_t c = p_serial1->getc(); + if(g_echoCount1 < 3){ // echoback is 3byte + if(++g_echoCount1 < 3){ + p_serial1->putc(g_cmd1[g_echoCount1]); // async + } + return; + } + /*if(g_echoCount1-- > 0){ // echoback is 3byte + return; + }*/ + + // motor response. + do { + g_res1[g_n1++] = c; + if(p_serial1->readable()) { + c = p_serial1->getc(); + } else break; + } while(1); + + if(g_n1 == 3){ // response is 3byte + // receive data set pre_deg + g_tx.d.motorData[g_id1] = ParseResponse(g_id1+1, g_res1, g_tx.d.motorData[g_id1]); + g_id1++; // 0-4 + + // last check + if(g_id1 == NUM_AXES1){ // motor num is 5 + g_finish |= BIT_SERIAL1; // receive finished +//d20=1;d20=0; + // next uart start + g_id2 = NUM_AXES1; // 5-8 + Serial2_puts(g_rx.d.motorData[g_id2]); // serial2 start + } else { + // next id send + Serial1_puts(g_rx.d.motorData[g_id1]); + } + } +} +static inline void Serial2_Rx(){ + g_next++; + // first is echoback. second is motor response. + uint8_t c = p_serial2->getc(); + if(g_echoCount2 < 3){ // echoback is 3byte + if(++g_echoCount2 < 3){ + p_serial2->putc(g_cmd2[g_echoCount2]); // async + } + return; + } + /*if(g_echoCount2-- > 0){ // echoback is 3byte + return; + }*/ + + // motor response. + do { + g_res2[g_n2++] = c; + if(p_serial2->readable()) { + c = p_serial2->getc(); + } else break; + } while(1); + + if(g_n2 == 3){ // response is 3byte + // receive data set pre_deg + g_tx.d.motorData[g_id2] = ParseResponse(g_id2+1, g_res2, g_tx.d.motorData[g_id2]); + g_id2++; // 0-3 + + // last check + if(g_id2 == NUM_AXES1 + NUM_AXES2){ // motor num is 4 + g_finish |= BIT_SERIAL2; // receive finished +//d20=1;d20=0; + } else { + // next id send + Serial2_puts(g_rx.d.motorData[g_id2]); + } + } +} + + + +static inline void setupUdp(void) { + EthernetInterface eth; + //serial_usb.printf("Setup UDP\n"); + eth.init(MY_ADDRESS, NETMASK, GATEWAY); + + //serial_usb.printf("eth.init()\n"); + int ret; + do { + ret = eth.connect(15000); // use dhcp + } while(ret < 0); + //serial_usb.printf("eth.connect()\n"); + + //const char *ip = eth.getIPAddress(); + //printf("IP: %s\n", ip ? ip : "No IP"); + r_sock.bind(PC_RX_PORT); //rx + s_sock.bind(PC_TX_PORT); //tx + //serial_usb.printf("Port: %d\n", MY_PORT); +} + +static inline void UdpReceive(){ + static uint16_t seq = 0; + //char buf[128]; + int ret = r_sock.receiveFrom(ep_pc_rx, g_rx.buf, sizeof(g_rx.buf)); + if(ret > 0){ +//UDP-RECEIVE +d24=1;d24=0; + + //__disable_irq(); + //memcpy(g_rx.buf, buf, sizeof(g_rx.buf)); + //__enable_irq(); + + if(g_rx.d.seq != seq){ // seq error + g_tx.d.dmy++; // seq error count +//ERROR +d22=1;d22=0; + } + if(g_rx.d.dmy == 1){ // err count clear request + g_rx.d.dmy = 0; + g_tx.d.dmy = 0; // err count clear + } + seq = g_rx.d.seq + 1; // next sequence + } +} + + +int main() { + float val; + int rate = 3; // Measuring rate -- 1:100S/s, 2:200S/s, 3:400S/s + int capdac[4] = {-1,-1,-1,-1}; // -1: CAPDAC disable, >=0: CAPDAC value + bool switchResult = true; + +/*--- Initialize -------------------------------------------------------------*/ + //ticker.attach(&tick_handler, 0.01); // 10us + +#if 1 + // udp initialized. + ep_pc_rx.set_address(PC_ADDRESS, PC_RX_PORT); + ep_pc_tx.set_address(PC_ADDRESS, PC_TX_PORT); + setupUdp(); + r_sock.set_blocking(false, 0); // non-blocking + s_sock.set_blocking(true, 1500); // blocking +#endif +#if 1 + // serial initialized + p_serial1 = new RawSerial(p13, p14); // uart1 + p_serial1->baud(ICS_BAUDRATE); + p_serial1->attach(Serial1_Rx, RawSerial::RxIrq); + p_serial1->format(8, Serial::Even, 1); + p_serial2 = new RawSerial(p17, p18); // uart3 + p_serial2->baud(ICS_BAUDRATE); + p_serial2->attach(Serial2_Rx, RawSerial::RxIrq); + p_serial2->format(8, Serial::Even, 1); +#endif +#if 1 + // i2c initialized + p_i2c1 = new I2C(p9, p10); // i2c1 sda,scl + p_i2c1->frequency(400000); + p_i2c2 = new I2C(p28, p27); // i2c2 sda,scl + p_i2c2->frequency(400000); +#endif +#if 1 + // Initialize I2C Interface + do{ + for(int i=0; i < FDC_NUM; i++) { + I2C *i2c = (i == 2)? p_i2c2 : p_i2c1; + + // MULTI PLEXER + if(i != 2){ + switchResult = switchI2c(i2c, i); // MUXのch0にI2Cを切替 + if(!switchResult) break; + } + + if (initFdc(i2c)) { + config(i2c, rate, capdac); + //pc.printf("ch %d_FDC1004 is ready.\r\n", i); + } else { + //pc.printf("ch %d_FDC1004 is not ready. Please check and restart.\r\n", i); + switchResult = false; + wait(1.0); + } + } // end_for + }while(!switchResult); +#endif + + // debug port + d26 = 0; + d25 = 0; + d24 = 0; + d23 = 0; + d22 = 0; + d21 = 0; + d20 = 0; + d19 = 0; + + g_finish = 0; + uint16_t seq = 0; + +/*--- MAIN LOOP --------------------------------------------------------------*/ + while(1) { + d19=!d19; //main-loop + +/*--- UDP RECEIVE (NON-BLOCKING) ---------------------------------------------*/ +#if 1 +d21=1; + UdpReceive(); +d21=0; +#endif + +/*--- SERIAL -----------------------------------------------------------------*/ +#if 1 + g_next = 0; + g_id1 = 0; //0-4 + Serial1_puts(g_rx.d.motorData[g_id1]); // serial1 start +#endif +/*--- I2C --------------------------------------------------------------------*/ +#if 1 + // Acquire sensor values + do{ + for (int j=0; j<FDC_NUM ;j++) { + I2C *i2c = (j == 2)? p_i2c2 : p_i2c1; + // MULTI PLEXER + if(j != 2){ + switchResult = switchI2c(i2c, j); + if(!switchResult) break; + } + senseCapacitance(i2c, g_tx.d.sensorData[j], capdac); + } + }while(!switchResult); +//d20=1;d20=0; + //g_finish |= BIT_I2C1; + //g_finish |= BIT_I2C2; +#endif +/*--- UDP SEND (BLOCKING) ----------------------------------------------------*/ +#if 1 + if((g_finish & 0x03) == 0x03){ // all data gathered +L001: +d20=1; + g_tx.d.seq = seq++; + int ret = s_sock.sendTo(ep_pc_tx, g_tx.buf, sizeof(g_tx.buf)); +d20=0; + if(ret != sizeof(g_tx.buf)){ // send error +//SEND-ERROR +d22=1;d22=0; + } + } else { +//GATHER-ERROR +led1=!led1; + //memset(&g_tx.d.motorData, 0, sizeof(g_tx.d.motorData)); // motor not needed + memset(&g_tx.d.sensorData, 0, sizeof(g_tx.d.sensorData)); // sensor is ZERO. + goto L001; + } + g_finish = 0; +#endif + + } // end_while(1) +} +
diff -r 000000000000 -r 88bfb16a6ad5 mbed-rtos.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed-rtos.lib Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/Kojto/code/mbed-rtos/#5713cbbdb706
diff -r 000000000000 -r 88bfb16a6ad5 mbed.bld --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/mbed_official/code/mbed/builds/65be27845400 \ No newline at end of file
diff -r 000000000000 -r 88bfb16a6ad5 mbed_config.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed_config.h Fri Apr 24 03:11:11 2020 +0000 @@ -0,0 +1,40 @@ +/* + * mbed SDK + * Copyright (c) 2017 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// Automatically generated configuration file. +// DO NOT EDIT, content will be overwritten. + +#ifndef __MBED_CONFIG_DATA__ +#define __MBED_CONFIG_DATA__ + +// Configuration parameters +#define MBED_CONF_PLATFORM_DEFAULT_SERIAL_BAUD_RATE 9600 // set by library:platform +#define MBED_CONF_PLATFORM_FORCE_NON_COPYABLE_ERROR 0 // set by library:platform +#define MBED_CONF_PLATFORM_STDIO_BAUD_RATE 9600 // set by library:platform +#define MBED_CONF_PLATFORM_STDIO_CONVERT_NEWLINES 0 // set by library:platform +#define MBED_CONF_PLATFORM_STDIO_FLUSH_AT_EXIT 1 // set by library:platform +#define MBED_CONF_TARGET_BOOT_STACK_SIZE 0x1000 // set by target:Target +#define MBED_CONF_TARGET_CONSOLE_UART 1 // set by target:Target +#define MBED_CONF_TARGET_DEEP_SLEEP_LATENCY 0 // set by target:Target +#define MBED_CONF_TARGET_INIT_US_TICKER_AT_BOOT 0 // set by target:Target +#define MBED_CONF_TARGET_MPU_ROM_END 0x0fffffff // set by target:Target +#define MBED_CONF_TARGET_NETWORK_DEFAULT_INTERFACE_TYPE ETHERNET // set by target:LPC1768 +#define MBED_CONF_TARGET_TICKLESS_FROM_US_TICKER 0 // set by target:Target +#define MBED_CONF_TARGET_US_TICKER_TIMER 3 // set by target:LPC1768 +#define MBED_CONF_TARGET_XIP_ENABLE 0 // set by target:Target + +#endif