sensorSign swicth
This commit is contained in:
parent
4b54887c6c
commit
354d9588bf
@ -79,7 +79,7 @@ class AP_ADC_HIL : public AP_ADC
|
||||
// @param index the axis for the accelerometer(0-x,1-y,2-z)
|
||||
inline void setAccel(uint8_t index, int16_t val) {
|
||||
int16_t temp = val * accelScale[index] / 1000 + accelBias[index];
|
||||
adcValue[sensors[index+3]] = (sensors[index+3] < 0) ? -temp : temp;
|
||||
adcValue[sensors[index+3]] = (sensorSign[index+3] < 0) ? -temp : temp;
|
||||
}
|
||||
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user