mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
desktop: added attachInterrupt() support
This commit is contained in:
parent
22c8db774f
commit
887ff43e1f
@ -156,3 +156,28 @@ char *ltoa(long __val, char *__s, int __radix)
|
||||
return __s;
|
||||
}
|
||||
|
||||
#define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
|
||||
|
||||
static struct {
|
||||
void (*call)(void);
|
||||
} interrupt_table[7];
|
||||
|
||||
void attachInterrupt(uint8_t inum, void (*call)(void), int mode)
|
||||
{
|
||||
if (inum >= ARRAY_LENGTH(interrupt_table)) {
|
||||
fprintf(stderr, "Bad attachInterrupt to interrupt %u\n", inum);
|
||||
exit(1);
|
||||
}
|
||||
interrupt_table[inum].call = call;
|
||||
}
|
||||
|
||||
void runInterrupt(uint8_t inum)
|
||||
{
|
||||
if (inum >= ARRAY_LENGTH(interrupt_table)) {
|
||||
fprintf(stderr, "Bad runInterrupt to interrupt %u\n", inum);
|
||||
exit(1);
|
||||
}
|
||||
if (interrupt_table[inum].call != NULL) {
|
||||
interrupt_table[inum].call();
|
||||
}
|
||||
}
|
||||
|
@ -86,6 +86,7 @@ void sitl_update_adc(float roll, float pitch, float yaw,
|
||||
UDR2.set(sensor_map[i], adc[i]);
|
||||
}
|
||||
|
||||
runInterrupt(6);
|
||||
|
||||
// set the airspeed sensor input
|
||||
UDR2.set(7, airspeed_sensor(airspeed));
|
||||
|
@ -6,3 +6,4 @@
|
||||
void set_nonblocking(int fd);
|
||||
double normalise(double v, double min, double max);
|
||||
double normalise180(double v);
|
||||
void runInterrupt(uint8_t inum);
|
||||
|
Loading…
Reference in New Issue
Block a user