Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/sensors/MagneticSensorPWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ float MagneticSensorPWM::getSensorAngle(){
int MagneticSensorPWM::getRawCount(){
if (!is_interrupt_based){ // if it's not interrupt based read the value in a blocking way
pulse_timestamp = _micros(); // ideally this should be done right at the rising edge of the pulse
pulse_length_us = pulseIn(pinPWM, HIGH, 1200); // 1200us timeout, should this be configurable?
pulse_length_us = pulseIn(pinPWM, HIGH, timeout_us); // 1200us timeout, should this be configurable?
}
return pulse_length_us;
}
Expand Down
2 changes: 2 additions & 0 deletions src/sensors/MagneticSensorPWM.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ class MagneticSensorPWM: public Sensor{
void enableInterrupt(void (*doPWM)());
unsigned long pulse_length_us;

unsigned int timeout_us = 1200;

private:
// raw count (typically in range of 0-1023)
int raw_count;
Expand Down