mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
Tools:HAL_Linux_Essentials: store pin status during pulse instead of status after pulse
This commit is contained in:
parent
210d3e8c32
commit
5e03df2d9a
@ -28,7 +28,7 @@ static inline u32 read_PIEP_COUNT(void)
|
||||
}
|
||||
|
||||
uint32_t read_pin(void){
|
||||
return ((__R31&(1<<15)) != 0) ;
|
||||
return ((__R31&(1<<15)) != 0);
|
||||
}
|
||||
|
||||
void main()
|
||||
@ -64,7 +64,7 @@ void main()
|
||||
uint32_t delta_time_us = now - last_time_us;
|
||||
last_time_us = now;
|
||||
|
||||
add_to_ring_buffer(v, delta_time_us);
|
||||
add_to_ring_buffer(last_pin_value, delta_time_us);
|
||||
last_pin_value = v;
|
||||
}
|
||||
}
|
||||
|
Binary file not shown.
Loading…
Reference in New Issue
Block a user