APM:Libraries
syscalls.c
Go to the documentation of this file.
1 /******************************************************************************
2  * The MIT License
3 
4 (c) 2017 night_ghost@ykoctpa.ru
5 
6 based on:
7 
8  * Copyright (c) 2010 Perry Hung.
9  *
10  * Permission is hereby granted, free of charge, to any person
11  * obtaining a copy of this software and associated documentation
12  * files (the "Software"), to deal in the Software without
13  * restriction, including without limitation the rights to use, copy,
14  * modify, merge, publish, distribute, sublicense, and/or sell copies
15  * of the Software, and to permit persons to whom the Software is
16  * furnished to do so, subject to the following conditions:
17  *
18  * The above copyright notice and this permission notice shall be
19  * included in all copies or substantial portions of the Software.
20  *
21  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
22  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
23  * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
24  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
25  * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
26  * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
27  * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
28  * SOFTWARE.
29  *****************************************************************************/
30 
31 #pragma GCC optimize ("O2")
32 
39 #include <syscalls.h>
40 #include <systick.h>
41 
42 /* _end and _eccm are set in the linker command file */
43 extern caddr_t _end;
44 extern caddr_t _eccm;
45 
46 #pragma GCC diagnostic ignored "-Wunused-variable"
47 
48 int _kill(int pid, int sig)
49 {
50  errno = EINVAL;
51  return -1;
52 }
53 
54 void _exit(int status)
55 {
56  __error(13, status, 0, 0);
57 }
58 
59 int _getpid(void)
60 {
61  return 1;
62 }
63 
64 
65 /*
66  * sbrk -- changes heap size. Get nbytes more
67  * RAM. We just increment a pointer in what's
68  * left of memory on the board.
69  */
70 
71 void *__brkval=0;
72 void *__brkval_ccm=0;
73 
74 caddr_t stack_bottom=0;
75 bool sbrk_need_dma=false;
76 
77 static caddr_t _sbrk_ram(int nbytes) {
78  static caddr_t heap_ptr = NULL;
79  caddr_t base;
80 
81  if (heap_ptr == NULL) {
82  heap_ptr = (caddr_t)&_end;
83  }
84 
85  uint32_t top = (uint32_t)get_stack_top();
86 
87  if ( top - 256 > (unsigned int)heap_ptr+nbytes // there is place in stack
88  || top < SRAM1_BASE /* 0x20000000*/ ) // or stack not in RAM
89  {
90  base = heap_ptr;
91  heap_ptr += nbytes;
92  __brkval = heap_ptr;
93  return (base);
94  } else {
95  return ((caddr_t)-1);
96  }
97 }
98 
99 static caddr_t _sbrk_ccm(int nbytes) {
100  static caddr_t heap_ptr = NULL;
101  caddr_t base;
102 
103  if (heap_ptr == NULL) {
104  heap_ptr = (caddr_t)&_eccm;
105  }
106 
107  uint32_t top = (uint32_t)get_stack_top() - 256; // reserve some memory
108 
109  if(stack_bottom) top = (uint32_t)stack_bottom;
110 
111  if ( top > (unsigned int)heap_ptr+nbytes) {// there is place in stack, if stack in RAM it will be true too
112  base = heap_ptr;
113  heap_ptr += nbytes;
114  __brkval_ccm = heap_ptr;
115  return (base);
116  } else {
117  return ((caddr_t)-1);
118  }
119 }
120 
121 caddr_t sbrk_ccm(int nbytes) {
122  nbytes = (nbytes & ~3)+4; // alignment
123  return _sbrk_ccm(nbytes);
124 }
125 
126 
127 caddr_t _sbrk(int nbytes) {
128  return _sbrk_ram(nbytes);
129 }
130 
131 
132 int _open(const char *path, int flags, ...) {
133  return 1;
134 }
135 
136 int _close(int fd) {
137  return 0;
138 }
139 
140 int _fstat(int fd, struct stat *st) {
141  st->st_mode = S_IFCHR;
142  return 0;
143 }
144 
145 int _isatty(int fd) {
146  return 1;
147 }
148 
149 int isatty(int fd) {
150  return 1;
151 }
152 
153 int _lseek(int fd, off_t pos, int whence) {
154  return -1;
155 }
156 
157 
158 void cgets(char *s, int bufsize) {
159  char *p;
160  int c;
161  int i;
162 
163  for (i = 0; i < bufsize; i++) {
164  *(s+i) = 0;
165  }
166 
167  p = s;
168 
169  for (p = s; p < s + bufsize-1;) {
170  c = getch();
171  switch (c) {
172  case '\r' :
173  case '\n' :
174  *p = '\n';
175  return;
176 
177  case '\b' :
178  if (p > s) {
179  *p-- = 0;
180  }
181  break;
182 
183  default :
184  *p++ = c;
185  break;
186  }
187  }
188  return;
189 }
190 
191 int _write(int fd, const char *buf, size_t cnt) {
192  size_t i;
193 
194  for (i = 0; i < cnt; i++)
195  putch(buf[i]);
196 
197  return cnt;
198 }
199 
200 
201 void clock_gettime(uint32_t a1, void *a2) { return; }
202 
203 int val_read(void *dest, volatile const void *src, int bytes)
204 {
205 
206  int i;
207 
208  for (i = 0; i < bytes / 4; i++) {
209  *(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i);
210  }
211 
212  return i * 4;
213 }
214 
215 
216 #define UDID_START 0x1FFF7A10
217 void get_board_serial(uint8_t *serialid)
218 {
219  const volatile uint32_t *udid_ptr = (const uint32_t *)UDID_START;
220  union udid id;
221 
222 #pragma GCC diagnostic push
223 #pragma GCC diagnostic ignored "-Wcast-align" // GCC lies in this warning - union udid already contains uint32_t
224 
225  val_read((uint32_t *)&id, udid_ptr, sizeof(id));
226 
227 #pragma GCC diagnostic pop
228 
229 
230  /* Copy the serial from the chips non-write memory and swap endianess */
231  serialid[0] = id.data[3]; serialid[1] = id.data[2]; serialid[2] = id.data[1]; serialid[3] = id.data[0];
232  serialid[4] = id.data[7]; serialid[5] = id.data[6]; serialid[6] = id.data[5]; serialid[7] = id.data[4];
233  serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8];
234 
235 }
caddr_t _end
caddr_t _sbrk(int nbytes)
Definition: syscalls.c:127
void putch(unsigned char c)
Definition: system.cpp:139
int _close(int fd)
Definition: syscalls.c:136
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
void get_board_serial(uint8_t *serialid)
Definition: syscalls.c:217
void * __brkval_ccm
Definition: syscalls.c:72
caddr_t stack_bottom
Definition: syscalls.c:74
Definition: syscalls.h:47
void * __brkval
Definition: syscalls.c:71
bool sbrk_need_dma
Definition: syscalls.c:75
int _open(const char *path, int flags,...)
Definition: syscalls.c:132
caddr_t sbrk_ccm(int nbytes)
Definition: syscalls.c:121
void _exit(int status)
Definition: syscalls.c:54
void __error(uint32_t num, uint32_t pc, uint32_t lr, uint32_t flag)
int _write(int fd, const char *buf, size_t cnt)
Definition: syscalls.c:191
void cgets(char *s, int bufsize)
Definition: syscalls.c:158
int _lseek(int fd, off_t pos, int whence)
Definition: syscalls.c:153
static caddr_t get_stack_top(void)
Definition: syscalls.h:19
int _getpid(void)
Definition: syscalls.c:59
int _isatty(int fd)
Definition: syscalls.c:145
#define UDID_START
Definition: syscalls.c:216
static caddr_t _sbrk_ram(int nbytes)
Definition: syscalls.c:77
int _kill(int pid, int sig)
Definition: syscalls.c:48
#define NULL
Definition: hal_types.h:59
caddr_t _eccm
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
unsigned char getch(void)
Definition: system.cpp:120
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int _fstat(int fd, struct stat *st)
Definition: syscalls.c:140
static caddr_t _sbrk_ccm(int nbytes)
Definition: syscalls.c:99
int val_read(void *dest, volatile const void *src, int bytes)
Definition: syscalls.c:203
int isatty(int fd)
Test POSIX fileno if it is a Serial Console/TTY.
Definition: syscalls.c:149