|
|
|
@ -17,6 +17,7 @@ char keyword_include[] = "include";
@@ -17,6 +17,7 @@ char keyword_include[] = "include";
|
|
|
|
|
char keyword_method[] = "method"; |
|
|
|
|
char keyword_operator[] = "operator"; |
|
|
|
|
char keyword_read[] = "read"; |
|
|
|
|
char keyword_scheduler_semaphore[] = "scheduler-semaphore"; |
|
|
|
|
char keyword_semaphore[] = "semaphore"; |
|
|
|
|
char keyword_singleton[] = "singleton"; |
|
|
|
|
char keyword_userdata[] = "userdata"; |
|
|
|
@ -299,6 +300,7 @@ struct userdata_field {
@@ -299,6 +300,7 @@ struct userdata_field {
|
|
|
|
|
|
|
|
|
|
enum userdata_flags { |
|
|
|
|
UD_FLAG_SEMAPHORE = (1U << 0), |
|
|
|
|
UD_FLAG_SCHEDULER_SEMAPHORE = (1U << 1), |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct userdata_enum { |
|
|
|
@ -788,6 +790,8 @@ void handle_singleton(void) {
@@ -788,6 +790,8 @@ void handle_singleton(void) {
|
|
|
|
|
|
|
|
|
|
} else if (strcmp(type, keyword_semaphore) == 0) { |
|
|
|
|
node->flags |= UD_FLAG_SEMAPHORE; |
|
|
|
|
} else if (strcmp(type, keyword_scheduler_semaphore) == 0) { |
|
|
|
|
node->flags |= UD_FLAG_SCHEDULER_SEMAPHORE; |
|
|
|
|
} else if (strcmp(type, keyword_method) == 0) { |
|
|
|
|
handle_method(node->name, &(node->methods)); |
|
|
|
|
} else if (strcmp(type, keyword_enum) == 0) { |
|
|
|
@ -845,12 +849,19 @@ void handle_ap_object(void) {
@@ -845,12 +849,19 @@ void handle_ap_object(void) {
|
|
|
|
|
|
|
|
|
|
} else if (strcmp(type, keyword_semaphore) == 0) { |
|
|
|
|
node->flags |= UD_FLAG_SEMAPHORE; |
|
|
|
|
} else if (strcmp(type, keyword_scheduler_semaphore) == 0) { |
|
|
|
|
node->flags |= UD_FLAG_SCHEDULER_SEMAPHORE; |
|
|
|
|
} else if (strcmp(type, keyword_method) == 0) { |
|
|
|
|
handle_method(node->name, &(node->methods)); |
|
|
|
|
} else { |
|
|
|
|
error(ERROR_SINGLETON, "AP_Objects only support aliases, methods or semaphore keyowrds (got %s)", type); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check that we didn't just add 2 singleton flags
|
|
|
|
|
if ((node->flags & UD_FLAG_SEMAPHORE) && (node->flags & UD_FLAG_SCHEDULER_SEMAPHORE)) { |
|
|
|
|
error(ERROR_SINGLETON, "Taking both a library semaphore and scheduler semaphore is prohibited"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// ensure no more tokens on the line
|
|
|
|
|
if (next_token()) { |
|
|
|
|
error(ERROR_HEADER, "Singleton contained an unexpected extra token: %s", state.token); |
|
|
|
@ -1345,6 +1356,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
@@ -1345,6 +1356,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|
|
|
|
fprintf(source, " ud->get_semaphore().take_blocking();\n"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (data->flags & UD_FLAG_SCHEDULER_SEMAPHORE) { |
|
|
|
|
fprintf(source, " AP::scheduler().get_semaphore().take_blocking();\n"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
switch (method->return_type.type) { |
|
|
|
|
case TYPE_BOOLEAN: |
|
|
|
|
fprintf(source, " const bool data = ud->%s(", method->name); |
|
|
|
@ -1433,6 +1448,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
@@ -1433,6 +1448,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|
|
|
|
fprintf(source, " ud->get_semaphore().give();\n"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (data->flags & UD_FLAG_SCHEDULER_SEMAPHORE) { |
|
|
|
|
fprintf(source, " AP::scheduler().get_semaphore().give();\n"); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
int return_count = 1; // number of arguments to return
|
|
|
|
|
switch (method->return_type.type) { |
|
|
|
|
case TYPE_BOOLEAN: |
|
|
|
|