00001 #include "hardware.h"
00002 #include <transport/can/can-net.h>
00003 #include <common/consts.h>
00004 #include <can/can.h>
00005 #include <dma/dma.h>
00006 #include <gpio/gpio.h>
00007 #include <uart/uart-software-fc.h>
00008 #include <clock/clock.h>
00009 #include <error/error.h>
00010 #include <types/types.h>
00011 #include <timer/timer.h>
00012 #include <ei/ei.h>
00013 #include <adc/adc.h>
00014
00015 #include "morse.h"
00016
00017
00018 _FWDT(FWDTEN_OFF);
00019 _FOSCSEL(FNOSC_FRCPLL);
00020 _FOSC(POSCMD_NONE & OSCIOFNC_ON);
00021
00022 _FICD(ICS_PGD1 & JTAGEN_OFF);
00023
00024 #define PRIO_CAN 5
00025 #define PRIO_UART 5
00026 #define PRIO_UART_TH 6
00027
00028 #define TIMER_UART TIMER_1
00029
00030
00031 #define SEND_QUEUE_SIZE 260
00032 static __attribute((far)) CanFrame sendQueue[SEND_QUEUE_SIZE];
00033 #define RECV_QUEUE_SIZE 1100
00034 static __attribute((far)) CanFrame recvQueue[RECV_QUEUE_SIZE];
00035
00036
00037 static __attribute((far)) __attribute((aligned(2))) unsigned char uartSendBuffer[ASEBA_MAX_PACKET_SIZE+4];
00038 static unsigned uartSendPos;
00039 static unsigned uartSendSize;
00040 static __attribute((far)) __attribute((aligned(2))) unsigned char uartRecvBuffer[ASEBA_MAX_PACKET_SIZE+4];
00041 static unsigned uartRecvPos;
00042
00043
00044
00045 volatile int global_flag = 0;
00046
00047 #define OUTPUT_ERROR(err) do{ for(;;) output_error(err,LED0,0,1); }while(0)
00048
00049 static void can_tx_cb(void)
00050 {
00051 if(global_flag)
00052 OUTPUT_ERROR(global_flag);
00053 global_flag = 1;
00054
00055 AsebaCanFrameSent();
00056
00057
00058
00059 if ((uartRecvPos >= 6) && (uartRecvPos == 6 + ((uint16 *)uartRecvBuffer)[0]))
00060 {
00061 uint16 source = ((uint16 *)uartRecvBuffer)[1];
00062 if (AsebaCanSendSpecificSource(uartRecvBuffer+4, uartRecvPos-4, source) == 1)
00063 {
00064 uartRecvPos = 0;
00065 uart_read_pending_data(U_UART);
00066 }
00067 }
00068 global_flag = 0;
00069 }
00070
00071 static void can_rx_cb(const can_frame* frame)
00072 {
00073 if(global_flag)
00074 OUTPUT_ERROR(global_flag);
00075 global_flag = 2;
00076
00077
00078 AsebaCanFrameReceived((CanFrame *) frame);
00079
00080 uint16 source;
00081
00082 if(uartSendPos == uartSendSize)
00083 {
00084 int amount = AsebaCanRecv(uartSendBuffer+4, ASEBA_MAX_PACKET_SIZE, &source);
00085 if (amount > 0)
00086 {
00087 ((uint16 *)uartSendBuffer)[0] = (uint16)amount - 2;
00088 ((uint16 *)uartSendBuffer)[1] = source;
00089 uartSendSize = (unsigned)amount + 4;
00090
00091 if(uart_transmit_byte(U_UART, uartSendBuffer[0]))
00092 uartSendPos = 1;
00093 else
00094 uartSendPos = 0;
00095 }
00096 }
00097 global_flag = 0;
00098
00099 }
00100
00101 static bool uart_rx_cb(int __attribute((unused)) uart_id, unsigned char data, void * __attribute((unused)) user_data)
00102 {
00103 if(global_flag)
00104 OUTPUT_ERROR(global_flag);
00105 global_flag = 3;
00106
00107
00108 uartRecvBuffer[uartRecvPos++] = data;
00109
00110
00111 if ((uartRecvPos >= 6) && (uartRecvPos == 6 + ((uint16 *)uartRecvBuffer)[0]))
00112 {
00113
00114 uint16 source = ((uint16 *)uartRecvBuffer)[1];
00115 if (AsebaCanSendSpecificSource(uartRecvBuffer+4, uartRecvPos-4, source) == 1)
00116 {
00117
00118 uartRecvPos = 0;
00119 global_flag = 0;
00120 return true;
00121 } else {
00122
00123 global_flag = 0;
00124 return false;
00125 }
00126 }
00127 global_flag = 0;
00128 return true;
00129 }
00130
00131 static bool uart_tx_cb(int __attribute((unused)) uart_id, unsigned char* data, void* __attribute((unused)) user_data)
00132 {
00133 if(global_flag)
00134 OUTPUT_ERROR(global_flag);
00135 global_flag = 4;
00136
00137 if (uartSendPos < uartSendSize)
00138 {
00139 *data = uartSendBuffer[uartSendPos++];
00140 global_flag = 0;
00141 return true;
00142 }
00143 else
00144 {
00145
00146
00147
00148 uint16 source;
00149
00150 int amount = AsebaCanRecv(uartSendBuffer+4, ASEBA_MAX_PACKET_SIZE, &source);
00151 if (amount > 0)
00152 {
00153 ((uint16 *)uartSendBuffer)[0] = (uint16)amount - 2;
00154 ((uint16 *)uartSendBuffer)[1] = source;
00155 uartSendSize = (unsigned)amount + 4;
00156 uartSendPos = 1;
00157 *data = uartSendBuffer[0];
00158 global_flag = 0;
00159 return true;
00160 }
00161
00162 global_flag = 0;
00163 return false;
00164 }
00165 }
00166
00167 void AsebaIdle(void) {
00168
00169 OUTPUT_ERROR(5);
00170 }
00171
00172 uint16 AsebaShouldDropPacket(uint16 source, const uint8* data) {
00173 return 0;
00174 }
00175
00176 static void received_packet_dropped(void)
00177 {
00178
00179 gpio_write(LED1, 0);
00180 }
00181
00182 static void sent_packet_dropped(void)
00183 {
00184
00185 gpio_write(LED1, 0);
00186 }
00187
00188 void __attribute__((noreturn)) error_handler(const char __attribute((unused)) * file, int __attribute((unused)) line, int id, void* __attribute((unused)) arg) {
00189 OUTPUT_ERROR(id);
00190 }
00191
00192
00193 int main(void)
00194 {
00195 int i;
00196
00197 if(_POR) {
00198 _POR = 0;
00199 asm __volatile("reset");
00200 }
00201
00202 clock_init_internal_rc_30();
00203
00204
00205
00206
00207 for(i = 0; i < 1000; i++)
00208 clock_delay_us(1000);
00209
00210 gpio_write(LED0, 1);
00211 gpio_write(LED1, 1);
00212 gpio_set_dir(LED0, GPIO_OUTPUT);
00213 gpio_set_dir(LED1, GPIO_OUTPUT);
00214
00215 error_register_callback(error_handler);
00216
00217
00218 adc1_init_simple(NULL, 1, 0x0UL, 30);
00219
00220 can_init(can_rx_cb, can_tx_cb, DMA_CHANNEL_0, DMA_CHANNEL_1, CAN_SELECT_MODE, 1000, PRIO_CAN);
00221 uart_init(U_UART, 921600, UART_CTS, UART_RTS, TIMER_UART, uart_rx_cb, uart_tx_cb, PRIO_UART_TH, PRIO_UART, NULL);
00222
00223 AsebaCanInit(0, (AsebaCanSendFrameFP)can_send_frame, can_is_frame_room, received_packet_dropped, sent_packet_dropped, sendQueue, SEND_QUEUE_SIZE, recvQueue, RECV_QUEUE_SIZE);
00224
00225
00226 while (1)
00227 {
00228
00229 Idle();
00230 };
00231 }
00232