mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
SITL: disable interrupts during register updates
this may prevent bogus mode channel reads
This commit is contained in:
parent
e445a455d0
commit
76736792f8
@ -26,6 +26,7 @@
|
||||
#include <AP_PeriodicProcess.h>
|
||||
#include <AP_TimerProcess.h>
|
||||
#include <GCS_MAVLink.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "sitl_adc.h"
|
||||
#include "sitl_rc.h"
|
||||
#include "desktop.h"
|
||||
@ -145,6 +146,7 @@ static void sitl_fdm_input(void)
|
||||
case 16: {
|
||||
// a packet giving the receiver PWM inputs
|
||||
uint8_t i;
|
||||
cli();
|
||||
for (i=0; i<8; i++) {
|
||||
// setup the ICR4 register for the RC channel
|
||||
// inputs
|
||||
@ -152,6 +154,7 @@ static void sitl_fdm_input(void)
|
||||
ICR4.set(i, d.pwm_pkt.pwm[i]);
|
||||
}
|
||||
}
|
||||
sei();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -11,6 +11,7 @@
|
||||
#include <sys/types.h>
|
||||
#include <math.h>
|
||||
#include <AP_ADC.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "wiring.h"
|
||||
#include "sitl_adc.h"
|
||||
#include "desktop.h"
|
||||
@ -88,17 +89,18 @@ void sitl_update_adc(float roll, float pitch, float yaw, // Relative to earth
|
||||
adc[5] = (zAccel / (_accel_scale * _sensor_signs[5])) + accel_offset;
|
||||
|
||||
/* tell the UDR2 register emulation what values to give to the driver */
|
||||
cli();
|
||||
for (uint8_t i=0; i<6; i++) {
|
||||
UDR2.set(sensor_map[i], adc[i]);
|
||||
}
|
||||
|
||||
runInterrupt(6);
|
||||
|
||||
// set the airspeed sensor input
|
||||
UDR2.set(7, airspeed_sensor(airspeed));
|
||||
|
||||
/* FIX: rubbish value for temperature for now */
|
||||
UDR2.set(3, 2000);
|
||||
sei();
|
||||
|
||||
runInterrupt(6);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user