00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include <string.h>
00025
00026
00027 #include <can/can.h>
00028 #include <dma/dma.h>
00029 #include <gpio/gpio.h>
00030 #include <types/types.h>
00031 #include <error/error.h>
00032 #include <flash/flash.h>
00033
00034
00035 #include <transport/can/can-net.h>
00036 #include <vm/natives.h>
00037 #include <vm/vm.h>
00038 #include <common/consts.h>
00039 #include <transport/buffer/vm-buffer.h>
00040
00041 #include "skel.h"
00042
00043
00044 static AsebaNativeFunctionDescription AsebaNativeDescription__system_reboot =
00045 {
00046 "_system.reboot",
00047 "Reboot the microcontroller",
00048 {
00049 { 0, 0 }
00050 }
00051 };
00052
00053 void AsebaResetIntoBootloader(AsebaVMState *vm) {
00054 asm __volatile__ ("reset");
00055 }
00056
00057 static AsebaNativeFunctionDescription AsebaNativeDescription__system_settings_read =
00058 {
00059 "_system.settings.read",
00060 "Read a setting",
00061 {
00062 { 1, "address"},
00063 { 1, "value"},
00064 { 0, 0 }
00065 }
00066 };
00067
00068 static void AsebaNative__system_settings_read(AsebaVMState *vm) {
00069 uint16 address = vm->variables[AsebaNativePopArg(vm)];
00070 uint16 destidx = AsebaNativePopArg(vm);
00071
00072 if(address > sizeof(settings)/2 - 1) {
00073 AsebaVMEmitNodeSpecificError(vm, "Address out of settings");
00074 return;
00075 }
00076 vm->variables[destidx] = ((unsigned int *) &settings)[address];
00077 }
00078
00079 static AsebaNativeFunctionDescription AsebaNativeDescription__system_settings_write =
00080 {
00081 "_system.settings.write",
00082 "Write a setting",
00083 {
00084 { 1, "address"},
00085 { 1, "value"},
00086 { 0, 0 }
00087 }
00088 };
00089
00090 static void AsebaNative__system_settings_write(AsebaVMState *vm) {
00091 uint16 address = vm->variables[AsebaNativePopArg(vm)];
00092 uint16 sourceidx = AsebaNativePopArg(vm);
00093 if(address > sizeof(settings)/2 - 1) {
00094 AsebaVMEmitNodeSpecificError(vm, "Address out of settings");
00095 return;
00096 }
00097 ((unsigned int *) &settings)[address] = vm->variables[sourceidx];
00098 }
00099
00100
00101 static AsebaNativeFunctionDescription AsebaNativeDescription__system_settings_flash =
00102 {
00103 "_system.settings.flash",
00104 "Write the settings into flash",
00105 {
00106 { 0, 0 }
00107 }
00108 };
00109
00110 static void AsebaNative__system_settings_flash(AsebaVMState *vm);
00111
00112
00113
00114 #include <skel-user.c>
00115
00116
00117 unsigned int events_flags = 0;
00118
00119
00120
00121 struct private_settings __attribute__((aligned(2))) settings;
00122
00123 #define COMPILATION_ASSERT(e) do { enum { assert_static__ = 1/(e) };} while(0)
00124
00125 const AsebaLocalEventDescription * AsebaGetLocalEventsDescriptions(AsebaVMState *vm)
00126 {
00127 return localEvents;
00128 }
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138 static __attribute((far)) CanFrame sendQueue[SEND_QUEUE_SIZE];
00139
00140 static __attribute((far)) CanFrame recvQueue[RECV_QUEUE_SIZE];
00141
00142
00143
00144 struct __attribute((far)) _vmVariables vmVariables;
00145
00146 static __attribute((far)) uint16 vmBytecode[VM_BYTECODE_SIZE];
00147
00148 static __attribute((far)) sint16 vmStack[VM_STACK_SIZE];
00149
00150 AsebaVMState vmState = {
00151 0,
00152
00153 VM_BYTECODE_SIZE,
00154 vmBytecode,
00155
00156 sizeof(vmVariables) / sizeof(sint16),
00157 (sint16*)&vmVariables,
00158
00159 VM_STACK_SIZE,
00160 vmStack
00161 };
00162
00163
00164
00165
00166
00167 void AsebaIdle(void) {
00168 Idle();
00169 }
00170
00171 void AsebaPutVmToSleep(AsebaVMState *vm) {
00172 }
00173
00174 void AsebaNativeFunction(AsebaVMState *vm, uint16 id)
00175 {
00176 nativeFunctions[id](vm);
00177 }
00178
00179
00180 static void received_packet_dropped(void)
00181 {
00182
00183 }
00184
00185 static void sent_packet_dropped(void)
00186 {
00187
00188 }
00189
00190 const AsebaVMDescription * AsebaGetVMDescription(AsebaVMState *vm) {
00191 return &vmDescription;
00192 }
00193
00194 uint16 AsebaShouldDropPacket(uint16 source, const uint8* data) {
00195 return AsebaVMShouldDropPacket(&vmState, source, data);
00196 }
00197
00198
00199 const AsebaNativeFunctionDescription * const * AsebaGetNativeFunctionsDescriptions(AsebaVMState *vm) {
00200 return nativeFunctionsDescription;
00201 }
00202
00203
00204
00205
00206
00207 #define PAGE_PER_CHUNK ((VM_BYTECODE_SIZE*2+3 + INSTRUCTIONS_PER_PAGE*3 - 1) / (INSTRUCTIONS_PER_PAGE*3))
00208 #if PAGE_PER_CHUNK == 0
00209 #undef PAGE_PER_CHUNK
00210 #define PAGE_PER_CHUNK 1
00211 #endif
00212
00213
00214
00215
00216
00217
00218 #define NUMBER_OF_CHUNK 26
00219 unsigned char aseba_flash[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode"), address(0x15800 - 0x800 - 0x400 - NUMBER_OF_CHUNK*0x400L*PAGE_PER_CHUNK)));
00220 unsigned char aseba_flash1[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00221 unsigned char aseba_flash2[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00222 unsigned char aseba_flash3[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00223 unsigned char aseba_flash4[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00224 unsigned char aseba_flash5[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00225 unsigned char aseba_flash6[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00226 unsigned char aseba_flash7[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00227 unsigned char aseba_flash8[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00228 unsigned char aseba_flash9[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00229 unsigned char aseba_flash10[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00230 unsigned char aseba_flash11[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00231 unsigned char aseba_flash12[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00232 unsigned char aseba_flash13[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00233 unsigned char aseba_flash14[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00234 unsigned char aseba_flash15[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00235 unsigned char aseba_flash16[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00236 unsigned char aseba_flash17[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00237 unsigned char aseba_flash18[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00238 unsigned char aseba_flash19[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00239 unsigned char aseba_flash20[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00240 unsigned char aseba_flash21[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00241 unsigned char aseba_flash22[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00242 unsigned char aseba_flash23[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00243 unsigned char aseba_flash24[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00244 unsigned char aseba_flash25[PAGE_PER_CHUNK][INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), aligned(INSTRUCTIONS_PER_PAGE * 2), section(".aseba_bytecode")));
00245
00246
00247 unsigned char __bootloader[INSTRUCTIONS_PER_PAGE * 2 * 2] __attribute((space(prog), section(".boot"), noload, address(0x15800 - 0x800)));
00248
00249
00250 unsigned char aseba_settings_flash[INSTRUCTIONS_PER_PAGE * 2] __attribute__ ((space(prog), section(".aseba_settings"), noload, address(0x15800 - 0x800 - 0x400)));
00251 #warning "the settings page is NOT initialised"
00252
00253
00254 unsigned long aseba_flash_ptr;
00255 unsigned long aseba_settings_ptr;
00256
00257 void AsebaWriteBytecode(AsebaVMState *vm) {
00258
00259 unsigned long min = 0xFFFFFFFF;
00260 unsigned long min_addr = 0;
00261 unsigned long count;
00262 unsigned int i;
00263 unsigned long temp_addr = aseba_flash_ptr;
00264 unsigned int instr_count;
00265 unsigned char * bcptr = (unsigned char *) vm->bytecode;
00266
00267 for (i = 0; i < NUMBER_OF_CHUNK; i++, temp_addr += INSTRUCTIONS_PER_PAGE * 2 * PAGE_PER_CHUNK) {
00268 count = flash_read_instr(temp_addr);
00269 if(count < min) {
00270 min = count;
00271 min_addr = temp_addr;
00272 }
00273 }
00274 if(min == 0xFFFFFFFF) {
00275 AsebaVMEmitNodeSpecificError(vm, "Error: min == 0xFFFFFFFF !");
00276 return;
00277 }
00278 min++;
00279
00280
00281 for(i = 0; i < PAGE_PER_CHUNK; i++)
00282 flash_erase_page(min_addr + i*INSTRUCTIONS_PER_PAGE * 2);
00283
00284
00285 flash_prepare_write(min_addr);
00286 flash_write_instruction(min);
00287 flash_write_buffer((unsigned char *) vm->bytecode, VM_BYTECODE_SIZE*2);
00288 flash_complete_write();
00289
00290
00291
00292
00293 if(min != flash_read_instr(min_addr)) {
00294 AsebaVMEmitNodeSpecificError(vm, "Error: Unable to flash bytecode (1) !");
00295 return;
00296 }
00297 min_addr += 2;
00298 instr_count = (VM_BYTECODE_SIZE*2) / 3;
00299
00300 for(i = 0; i < instr_count; i++) {
00301 unsigned char data[3];
00302 flash_read_chunk(min_addr, 3, data);
00303
00304 if(memcmp(data, bcptr, 3)) {
00305 AsebaVMEmitNodeSpecificError(vm, "Error: Unable to flash bytecode (2) !");
00306 return;
00307 }
00308 bcptr += 3;
00309 min_addr += 2;
00310 }
00311
00312 i = (VM_BYTECODE_SIZE * 2) % 3;
00313
00314 if(i != 0) {
00315 unsigned char data[2];
00316 flash_read_chunk(min_addr, i, data);
00317 if(memcmp(data, bcptr, i)) {
00318 AsebaVMEmitNodeSpecificError(vm, "Error: Unable to flash bytecode (3) !");
00319 return;
00320 }
00321 }
00322
00323 AsebaVMEmitNodeSpecificError(vm, "Flashing OK");
00324
00325 }
00326
00327 const static unsigned int _magic_[8] = {0xDE, 0xAD, 0xCA, 0xFE, 0xBE, 0xEF, 0x04, 0x02};
00328 static void AsebaNative__system_settings_flash(AsebaVMState *vm) {
00329
00330
00331
00332
00333
00334 unsigned long setting_addr = aseba_settings_ptr;
00335 int i = 0;
00336 unsigned int mag;
00337 unsigned long temp;
00338 for(i = 0; i < 8; i++) {
00339 mag = flash_read_low(setting_addr + INSTRUCTIONS_PER_ROW * 2 * i);
00340 if(mag != _magic_[i])
00341 break;
00342 }
00343
00344 if(i == 0 || i == 8) {
00345 flash_erase_page(setting_addr);
00346 i = 0;
00347 }
00348
00349 setting_addr += INSTRUCTIONS_PER_ROW * 2 * i;
00350
00351 flash_prepare_write(setting_addr);
00352 temp = (((unsigned long) *((unsigned char * ) &settings)) << 16) | _magic_[i];
00353
00354 flash_write_instruction(temp);
00355 flash_write_buffer(((unsigned char *) &settings) + 1, sizeof(settings) - 1);
00356 flash_complete_write();
00357 }
00358
00359 static void load_code_from_flash(AsebaVMState *vm) {
00360
00361 unsigned long max = 0;
00362 unsigned long max_addr = 0;
00363 unsigned long temp_addr = aseba_flash_ptr;
00364 unsigned long count;
00365 unsigned int i;
00366
00367 for (i = 0; i < NUMBER_OF_CHUNK; i++, temp_addr += INSTRUCTIONS_PER_PAGE * 2 * PAGE_PER_CHUNK) {
00368 count = flash_read_instr(temp_addr);
00369 if(count >= max) {
00370 max = count;
00371 max_addr = temp_addr;
00372 }
00373 }
00374 if(!max)
00375
00376 return;
00377
00378 flash_read_chunk(max_addr + 2, VM_BYTECODE_SIZE*2, (unsigned char *) vm->bytecode);
00379
00380
00381 AsebaVMSetupEvent(vm, ASEBA_EVENT_INIT);
00382 }
00383
00384 int load_settings_from_flash(void) {
00385
00386
00387 COMPILATION_ASSERT(sizeof(settings) < ((INSTRUCTIONS_PER_ROW*3) - 2));
00388 COMPILATION_ASSERT(sizeof(settings) > 1);
00389
00390
00391 unsigned long temp = aseba_settings_ptr;
00392 int i = 0;
00393 unsigned int mag;
00394
00395
00396
00397 for(i = 0; i < 8; i++) {
00398 mag = flash_read_low(temp + INSTRUCTIONS_PER_ROW * 2 * i);
00399 if(mag != _magic_[i])
00400 break;
00401 }
00402 if(i == 0)
00403
00404 return -1;
00405 i--;
00406 temp += INSTRUCTIONS_PER_ROW * 2 * i;
00407 *((unsigned char *) &settings) = (unsigned char) (flash_read_high(temp) & 0xFF);
00408 flash_read_chunk(temp + 2, sizeof(settings) - 1, ((unsigned char *) &settings) + 1);
00409
00410 return 0;
00411 }
00412
00413
00414
00415 #ifdef ASEBA_ASSERT
00416 void AsebaAssert(AsebaVMState *vm, AsebaAssertReason reason) {
00417 AsebaVMEmitNodeSpecificError(vm, "VM ASSERT !");
00418 }
00419 #endif
00420
00421 static unsigned int ui2str(char *str, unsigned int value) {
00422 unsigned div;
00423 unsigned int i = 0;
00424 bool hasSent = false;
00425 for (div = 10000; div > 0; div /= 10)
00426 {
00427 unsigned disp = value / div;
00428 value %= div;
00429
00430 if ((disp != 0) || (hasSent) || (div == 1))
00431 {
00432 hasSent = true;
00433 str[i++] = '0' + disp;
00434 }
00435 }
00436 str[i] = 0;
00437 return i;
00438 }
00439
00440 static unsigned int ui2strhex(char * str, unsigned int id) {
00441 int shift;
00442 bool hasSent = false;
00443 unsigned int i = 0;
00444 for (shift = 12; shift >= 0; shift -= 4)
00445 {
00446 unsigned disp = ((id & (0xF << shift)) >> shift);
00447
00448 if ((disp != 0) || (hasSent) || (shift == 0))
00449 {
00450 hasSent = true;
00451 if(disp > 9)
00452 str[i++] = 'A' + disp - 0xA;
00453 else
00454 str[i++] = '0' + disp;
00455 }
00456 }
00457 str[i] = 0;
00458 return i;
00459 }
00460
00461 static void __attribute__((noreturn)) error_handler(const char * file, int line, int id, void* __attribute((unused)) arg) {
00462 char error_string[255];
00463 char number[10];
00464 strcpy(error_string, "Molole error 0x");
00465 ui2strhex(number, (unsigned int) id);
00466 strcat(error_string, number);
00467 strcat(error_string, " in file: ");
00468 strncat(error_string, file, 200);
00469 strcat(error_string, ":");
00470 ui2str(number, line);
00471 strcat(error_string, number);
00472
00473
00474 AsebaVMEmitNodeSpecificError(&vmState, error_string);
00475
00476 AsebaCanFlushQueue();
00477
00478 asm __volatile__ ("reset");
00479
00480 for(;;);
00481 }
00482
00483 #define FUID3 0xF80016
00484
00485 void init_aseba_and_can(void) {
00486 unsigned int low, high;
00487
00488
00489 vmState.nodeId = flash_read_low(FUID3);
00490
00491
00492 asm ("mov #tbloffset(.startof.(.aseba_bytecode)), %[l]" : [l] "=r" (low));
00493 asm ("mov #tblpage(.startof.(.aseba_bytecode)), %[h]" : [h] "=r" (high));
00494 aseba_flash_ptr = (unsigned long) high << 16 | low;
00495
00496 asm ("mov #tbloffset(.startof.(.aseba_settings)), %[l]" : [l] "=r" (low));
00497 asm ("mov #tblpage(.startof.(.aseba_settings)), %[h]" : [h] "=r" (high));
00498 aseba_settings_ptr = (unsigned long) high << 16 | low;
00499
00500
00501
00502 can_init((can_frame_received_callback)AsebaCanFrameReceived, AsebaCanFrameSent, DMA_CAN_RX, DMA_CAN_TX, CAN_SELECT_MODE, 1000, PRIO_CAN);
00503 AsebaCanInit(vmState.nodeId, (AsebaCanSendFrameFP)can_send_frame, can_is_frame_room, received_packet_dropped, sent_packet_dropped, sendQueue, SEND_QUEUE_SIZE, recvQueue, RECV_QUEUE_SIZE);
00504 AsebaVMInit(&vmState);
00505 vmVariables.id = vmState.nodeId;
00506
00507 load_code_from_flash(&vmState);
00508
00509 error_register_callback(error_handler);
00510
00511 }
00512
00513 void __attribute((noreturn)) run_aseba_main_loop(void) {
00514 while(1)
00515 {
00516 update_aseba_variables_read();
00517
00518 AsebaVMRun(&vmState, 1000);
00519
00520 AsebaProcessIncomingEvents(&vmState);
00521
00522 update_aseba_variables_write();
00523
00524
00525
00526 if (AsebaMaskIsSet(vmState.flags, ASEBA_VM_STEP_BY_STEP_MASK) || AsebaMaskIsClear(vmState.flags, ASEBA_VM_EVENT_ACTIVE_MASK))
00527 {
00528 unsigned i;
00529
00530
00531
00532
00533
00534 asm __volatile__ ("mov #SR, w0 \r\n"
00535 "mov #0xC0, w1\r\n"
00536 "ior.b w1, [w0], [w0]\r\n"
00537 "ff1r [%[word]], %[b]\r\n"
00538 "bra nc, 1f\r\n"
00539 "rcall _AsebaCanRecvBufferEmpty\r\n"
00540 "cp0 w0\r\n"
00541 "bra z, 1f \r\n"
00542 "rcall _clock_idle\r\n"
00543 "1: \r\n"
00544 "mov #SR, w0 \r\n"
00545 "mov #0x1F, w1\r\n"
00546 "and.b w1, [w0],[w0] \r\n"
00547 : [b] "=x" (i) : [word] "r" (&events_flags) : "cc", "w0", "w1", "w2", "w3", "w4", "w5", "w6", "w7");
00548
00549
00550
00551
00552
00553
00554
00555 if(i && !(AsebaMaskIsSet(vmState.flags, ASEBA_VM_STEP_BY_STEP_MASK) && AsebaMaskIsSet(vmState.flags, ASEBA_VM_EVENT_ACTIVE_MASK))) {
00556
00557
00558 i--;
00559 CLEAR_EVENT(i);
00560 vmVariables.source = vmState.nodeId;
00561 AsebaVMSetupEvent(&vmState, ASEBA_EVENT_LOCAL_EVENTS_START - i);
00562 }
00563 }
00564 }
00565 }
00566
00567